diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml new file mode 100644 index 000000000000..efc5972325f6 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -0,0 +1,178 @@ +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/bugfix-2.1.x/.github/code_of_conduct.md). You are expected to comply with it, including treating everyone with respect. + + - Test with the [`bugfix-2.1.x` branch](https://github.com/MarlinFirmware/Marlin/archive/bugfix-2.1.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/bugfix-2.1.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.1.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.1.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. + + When pasting formatted text don't forget to put ` ``` ` (on its own line) before and after to make it readable. + 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: | + # Attachments + + - type: checkboxes + attributes: + label: Don't forget to include + options: + - label: A ZIP file containing your `Configuration.h` and `Configuration_adv.h`. + required: true + + - type: markdown + attributes: + value: | + ### Optional items to include: + - '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. + + - type: textarea + attributes: + label: Additional information & file uploads + description: >- + If you've made any other modifications to the firmware, please describe them in detail. + + When pasting formatted text don't forget to put ` ``` ` (on its own line) before and after to make it readable. diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml new file mode 100644 index 000000000000..1fe68966fbba --- /dev/null +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -0,0 +1,20 @@ +blank_issues_enabled: false +contact_links: + - name: 📖 Marlin Documentation + url: https://marlinfw.org/ + about: Lots of documentation on installing and using Marlin. + - name: 👤 MarlinFirmware Facebook group + url: https://www.facebook.com/groups/1049718498464482 + about: Please ask and answer questions here. + - name: 🕹 Marlin on Discord + url: https://discord.gg/n5NJ59y + about: Join the Discord server for support and discussion. + - name: 🔗 Marlin Discussion Forum + url: https://reprap.org/forum/list.php?415 + about: A searchable web forum hosted by RepRap dot org. + - 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.yml b/.github/ISSUE_TEMPLATE/feature_request.yml new file mode 100644 index 000000000000..b64383cd48b2 --- /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.1.x` branch](https://github.com/MarlinFirmware/Marlin/archive/bugfix-2.1.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/contributing.md b/.github/contributing.md index 6bc7b5a00514..fcb87b014123 100644 --- a/.github/contributing.md +++ b/.github/contributing.md @@ -50,13 +50,13 @@ If chat is more your speed, you can join the MarlinFirmware Discord server: This section guides you through submitting a Bug Report for Marlin. Following these guidelines helps maintainers and the community understand your report, reproduce the behavior, and find related reports. -Before creating a Bug Report, please test the "nightly" development branch, as you might find out that you don't need to create one. When you are creating a Bug Report, please [include as many details as possible](#how-do-i-submit-a-good-bug-report). Fill out [the required template](issue_template.md), the information it asks for helps us resolve issues faster. +Before creating a Bug Report, please test the "nightly" development branch, as you might find out that you don't need to create one. When you are creating a Bug Report, please [include as many details as possible](#how-do-i-submit-a-good-bug-report). Fill out [the required template](ISSUE_TEMPLATE/bug_report.yml), the information it asks for helps us resolve issues faster. > **Note:** Regressions can happen. If you find a **Closed** issue that seems like your issue, go ahead and open a new issue and include a link to the original issue in the body of your new one. All you need to create a link is the issue number, preceded by #. For example, #8888. #### How Do I Submit A (Good) Bug Report? -Bugs are tracked as [GitHub issues](https://guides.github.com/features/issues/). Use the New Issue button to create an issue and provide the following information by filling in [the template](issue_template.md). +Bugs are tracked as [GitHub issues](https://guides.github.com/features/issues/). Use the New Issue button to create an issue and provide the following information by filling in [the template](ISSUE_TEMPLATE/bug_report.yml). Explain the problem and include additional details to help maintainers reproduce the problem: @@ -88,12 +88,12 @@ Include details about your configuration and environment: This section guides you through submitting a suggestion for Marlin, including completely new features and minor improvements to existing functionality. Following these guidelines helps maintainers and the community understand your suggestion and find related suggestions. -Before creating a suggestion, please check [this list](#before-submitting-a-suggestion) as you might find out that you don't need to create one. When you are creating an enhancement suggestion, please [include as many details as possible](#how-do-i-submit-a-good-enhancement-suggestion). Fill in [the template](issue_template.md), including the steps that you imagine you would take if the feature you're requesting existed. +Before creating a suggestion, please check [this list](https://github.com/MarlinFirmware/Marlin/issues?q=is%3Aopen+is%3Aissue+label%3A%22T%3A+Feature+Request%22) as you might find out that you don't need to create one. When you are creating an enhancement suggestion, please [include as many details as possible](#how-do-i-submit-a-good-feature-request). Fill in [the template](ISSUE_TEMPLATE/feature_request.yml), including the steps that you imagine you would take if the feature you're requesting existed. #### Before Submitting a Feature Request * **Check the [Marlin website](https://marlinfw.org/)** for tips — you might discover that the feature is already included. Most importantly, check if you're using [the latest version of Marlin](https://github.com/MarlinFirmware/Marlin/releases) and if you can get the desired behavior by changing [Marlin's config settings](https://marlinfw.org/docs/configuration/configuration.html). -* **Perform a [cursory search](https://github.com/MarlinFirmware/Marlin/issues?q=is%3Aissue)** to see if the enhancement has already been suggested. If it has, add a comment to the existing issue instead of opening a new one. +* **Perform a [cursory search](https://github.com/MarlinFirmware/Marlin/issues?q=is%3Aopen+is%3Aissue+label%3A%22T%3A+Feature+Request%22)** to see if the enhancement has already been suggested. If it has, add a comment to the existing issue instead of opening a new one. #### How Do I Submit A (Good) Feature Request? @@ -116,7 +116,7 @@ Unsure where to begin contributing to Marlin? You can start by looking through t ### Pull Requests -Pull Requests should always be targeted to working branches (e.g., `bugfix-1.1.x` and/or `bugfix-2.0.x`) and never to release branches (e.g., `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation. +Pull Requests should always be targeted to working branches (e.g., `bugfix-2.1.x` and/or `bugfix-1.1.x`) and never to release branches (e.g., `2.0.x` and/or `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation. * Fill in [the required template](pull_request_template.md). * Don't include issue numbers in the PR title. diff --git a/.github/issue_template.md b/.github/issue_template.md deleted file mode 100644 index 6cb34b8f588a..000000000000 --- a/.github/issue_template.md +++ /dev/null @@ -1,35 +0,0 @@ - - -### 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 new file mode 100644 index 000000000000..51b58ad493f0 --- /dev/null +++ b/.github/workflows/bump-date.yml @@ -0,0 +1,59 @@ +# +# bump-date.yml +# Bump the distribution date once per day +# + +name: Bump Distribution Date + +on: + schedule: + - cron: '0 */6 * * *' + +jobs: + bump_date: + name: Bump Distribution Date + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-latest + + steps: + + - name: Check out bugfix-2.1.x + uses: actions/checkout@v2 + with: + ref: bugfix-2.1.x + + - name: Bump Date (bugfix-2.0.x) + run: | + # Inline Bump Script + if [[ ! "$( git log -1 --pretty=%B )" =~ ^\[cron\] ]]; then + 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 . && \ + git commit -m "[cron] Bump distribution date ($DIST)" && \ + git push + fi + exit 0 + + - name: Check out bugfix-2.1.x + uses: actions/checkout@v2 + with: + ref: bugfix-2.1.x + + - name: Bump Date (bugfix-2.1.x) + run: | + # Inline Bump Script + if [[ ! "$( git log -1 --pretty=%B )" =~ ^\[cron\] ]]; then + 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 . && \ + git commit -m "[cron] Bump distribution date ($DIST)" && \ + git push + fi + exit 0 diff --git a/.github/workflows/check-pr.yml b/.github/workflows/check-pr.yml new file mode 100644 index 000000000000..79d0b5e2d041 --- /dev/null +++ b/.github/workflows/check-pr.yml @@ -0,0 +1,34 @@ +# +# check-pr.yml +# Close PRs directed at release branches +# + +name: PR Bad Target + +on: + pull_request_target: + types: [opened] + branches: + - 1.0.x + - 1.1.x + - 2.0.x + - 2.1.x + +jobs: + bad_target: + name: PR Bad Target + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-latest + + steps: + - uses: superbrothers/close-pull-request@v3 + with: + 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. + + Please redo this PR starting with the `bugfix-2.1.x` branch and be careful to target `bugfix-2.1.x` when resubmitting the PR. Patches may also target `bugfix-2.0.x` if they are specifically for 2.0.9.x. + + It may help to set your fork's default branch to `bugfix-2.0.x`. + + See [this page](http://marlinfw.org/docs/development/getting_started_pull_requests.html) for full instructions. 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 new file mode 100644 index 000000000000..f90c079f6605 --- /dev/null +++ b/.github/workflows/close-stale.yml @@ -0,0 +1,28 @@ +# +# close-stale.yml +# Close open issues after a period of inactivity +# + +name: Close Stale Issues + +on: + schedule: + - cron: "22 1 * * *" + +jobs: + stale: + name: Close Stale Issues + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-latest + + steps: + - uses: actions/stale@v3 + with: + repo-token: ${{ secrets.GITHUB_TOKEN }} + 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-all-assignees: true + exempt-issue-labels: 'Bug: Confirmed !,T: Feature Request,Needs: Discussion,Needs: Documentation,Needs: Patch,Needs: Work,Needs: Testing,help wanted,no-locking' diff --git a/.github/workflows/lock-closed.yml b/.github/workflows/lock-closed.yml new file mode 100644 index 000000000000..8cdcd7a8369e --- /dev/null +++ b/.github/workflows/lock-closed.yml @@ -0,0 +1,32 @@ +# +# lock-closed.yml +# Lock closed issues after a period of inactivity +# + +name: Lock Closed Issues + +on: + schedule: + - cron: '0 1/13 * * *' + +jobs: + lock: + name: Lock Closed Issues + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-latest + + steps: + - uses: dessant/lock-threads@v2 + with: + github-token: ${{ github.token }} + process-only: 'issues' + issue-lock-inactive-days: '60' + issue-exclude-created-before: '' + issue-exclude-labels: 'no-locking' + issue-lock-labels: '' + issue-lock-comment: > + This issue has been automatically locked since there + has not been any recent activity after it was closed. + Please open a new issue for related bugs. + issue-lock-reason: '' diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 75cd6ee05fe7..e2418f38a6dd 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -9,6 +9,7 @@ on: pull_request: branches: - bugfix-2.0.x + - bugfix-2.1.x paths-ignore: - config/** - data/** @@ -17,6 +18,7 @@ on: push: branches: - bugfix-2.0.x + - bugfix-2.1.x paths-ignore: - config/** - data/** @@ -59,7 +61,7 @@ jobs: #- STM32F103RC_btt_maple - STM32F103RC_btt_USB_maple - STM32F103RC_fysetc_maple - - STM32F103RC_meeb + - STM32F103RC_meeb_maple - jgaurora_a5s_a1_maple - STM32F103VE_longer_maple #- mks_robin_maple @@ -76,6 +78,7 @@ jobs: - STM32F103RE_btt - STM32F103RE_btt_USB - STM32F103RE_creality + - STM32F401RC_creality - STM32F103VE_longer - STM32F407VE_black - STM32F401VE_STEVAL @@ -97,7 +100,7 @@ jobs: - REMRAM_V1 - BTT_SKR_SE_BX - chitu_f103 - - Index_Mobo_Rev03 + - Opulo_Lumen_REV3 # Put lengthy tests last @@ -137,8 +140,9 @@ jobs: - name: Install PlatformIO run: | - pip install -U https://github.com/platformio/platformio-core/archive/develop.zip - platformio update + pip install -U platformio + pio upgrade --dev + pio pkg update --global - name: Run ${{ matrix.test-platform }} Tests run: | diff --git a/.github/workflows/unlock-reopened.yml b/.github/workflows/unlock-reopened.yml new file mode 100644 index 000000000000..614ef3fab297 --- /dev/null +++ b/.github/workflows/unlock-reopened.yml @@ -0,0 +1,22 @@ +# +# unlock-reopened.yml +# Unlock an issue whenever it is re-opened +# + +name: "Unlock reopened issue" + +on: + issues: + types: [reopened] + +jobs: + unlock: + name: Unlock Reopened + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-latest + + steps: + - uses: OSDKDev/unlock-issues@v1.1 + with: + repo-token: "${{ secrets.GITHUB_TOKEN }}" diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index b06a2cafbc78..e05428ad08d8 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -35,7 +35,7 @@ * * Advanced settings can be found in Configuration_adv.h */ -#define CONFIGURATION_H_VERSION 02010000 +#define CONFIGURATION_H_VERSION 02010100 //=========================================================================== //============================= Getting Started ============================= @@ -57,15 +57,6 @@ * https://www.thingiverse.com/thing:1278865 */ -//=========================================================================== -//========================== DELTA / SCARA / TPARA ========================== -//=========================================================================== -// -// Download configurations from the link above and customize for your machine. -// Examples are located in config/examples/delta, .../SCARA, and .../TPARA. -// -//=========================================================================== - // @section info // Author info of this build printed to the host during boot and M115 @@ -150,20 +141,43 @@ //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" /** - * Define the number of coordinated axes. - * See https://github.com/DerAndere1/Marlin/wiki - * Each axis gets its own stepper control and endstop: + * Stepper Drivers + * + * These settings allow Marlin to tune stepper driver timing and enable advanced options for + * stepper drivers that support them. You may also override timing options in Configuration_adv.h. * - * 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 + * Use TMC2208/TMC2208_STANDALONE for TMC2225 drivers and TMC2209/TMC2209_STANDALONE for TMC2226 drivers. * - * :[3, 4, 5, 6, 7, 8, 9] + * Options: A4988, A5984, DRV8825, LV8729, L6470, L6474, POWERSTEP01, + * TB6560, TB6600, TMC2100, + * TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE, + * TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE, + * TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE, + * TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE + * :['A4988', 'A5984', 'DRV8825', 'LV8729', 'L6470', 'L6474', 'POWERSTEP01', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] */ -//#define NUM_AXES 3 +#define X_DRIVER_TYPE A4988 +#define Y_DRIVER_TYPE A4988 +#define Z_DRIVER_TYPE A4988 +//#define X2_DRIVER_TYPE A4988 +//#define Y2_DRIVER_TYPE A4988 +//#define Z2_DRIVER_TYPE A4988 +//#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 U_DRIVER_TYPE A4988 +//#define V_DRIVER_TYPE A4988 +//#define W_DRIVER_TYPE A4988 +#define E0_DRIVER_TYPE A4988 +//#define E1_DRIVER_TYPE A4988 +//#define E2_DRIVER_TYPE A4988 +//#define E3_DRIVER_TYPE A4988 +//#define E4_DRIVER_TYPE A4988 +//#define E5_DRIVER_TYPE A4988 +//#define E6_DRIVER_TYPE A4988 +//#define E7_DRIVER_TYPE A4988 /** * Additional Axis Settings @@ -182,27 +196,27 @@ * * Regardless of these settings the axes are internally named I, J, K, U, V, W. */ -#if NUM_AXES >= 4 +#ifdef I_DRIVER_TYPE #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W'] #define AXIS4_ROTATES #endif -#if NUM_AXES >= 5 +#ifdef J_DRIVER_TYPE #define AXIS5_NAME 'B' // :['B', 'C', 'U', 'V', 'W'] #define AXIS5_ROTATES #endif -#if NUM_AXES >= 6 +#ifdef K_DRIVER_TYPE #define AXIS6_NAME 'C' // :['C', 'U', 'V', 'W'] #define AXIS6_ROTATES #endif -#if NUM_AXES >= 7 +#ifdef U_DRIVER_TYPE #define AXIS7_NAME 'U' // :['U', 'V', 'W'] //#define AXIS7_ROTATES #endif -#if NUM_AXES >= 8 +#ifdef V_DRIVER_TYPE #define AXIS8_NAME 'V' // :['V', 'W'] //#define AXIS8_ROTATES #endif -#if NUM_AXES >= 9 +#ifdef W_DRIVER_TYPE #define AXIS9_NAME 'W' // :['W'] //#define AXIS9_ROTATES #endif @@ -620,7 +634,7 @@ #if ENABLED(PIDTEMP) //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) - // Set/get with gcode: M301 E[extruder number, 0-2] + // Set/get with G-code: M301 E[extruder number, 0-2] #if ENABLED(PID_PARAMS_PER_HOTEND) // Specify up to one value per hotend here, according to your setup. @@ -665,15 +679,15 @@ //#define MPC_FAN_0_ACTIVE_HOTEND #endif - #define FILAMENT_HEAT_CAPACITY_PERMM 5.6e-3f // 0.0056 J/K/mm for 1.75mm PLA (0.0149 J/K/mm for 2.85mm PLA). - //#define FILAMENT_HEAT_CAPACITY_PERMM 3.6e-3f // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG). + #define FILAMENT_HEAT_CAPACITY_PERMM { 5.6e-3f } // 0.0056 J/K/mm for 1.75mm PLA (0.0149 J/K/mm for 2.85mm PLA). + //#define FILAMENT_HEAT_CAPACITY_PERMM { 3.6e-3f } // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG). // Advanced options #define MPC_SMOOTHING_FACTOR 0.5f // (0.0...1.0) Noisy temperature sensors may need a lower value for stabilization. #define MPC_MIN_AMBIENT_CHANGE 1.0f // (K/s) Modeled ambient temperature rate of change, when correcting model inaccuracies. #define MPC_STEADYSTATE 0.5f // (K/s) Temperature change rate for steady state logic to be enforced. - #define MPC_TUNING_POS { X_CENTER, Y_CENTER, 1.0f } // (mm) M306 Autotuning position, ideally bed center just above the surface. + #define MPC_TUNING_POS { X_CENTER, Y_CENTER, 1.0f } // (mm) M306 Autotuning position, ideally bed center at first layer height. #define MPC_TUNING_END_Z 10.0f // (mm) M306 Autotuning final Z position. #endif @@ -842,6 +856,141 @@ #define POLAR_SEGMENTS_PER_SECOND 5 #endif +// Enable for DELTA kinematics and configure below +//#define DELTA +#if ENABLED(DELTA) + + // Make delta curves from many straight lines (linear interpolation). + // This is a trade-off between visible corners (not enough segments) + // and processor overload (too many expensive sqrt calls). + #define DELTA_SEGMENTS_PER_SECOND 200 + + // After homing move down to a height where XY movement is unconstrained + //#define DELTA_HOME_TO_SAFE_ZONE + + // Delta calibration menu + // uncomment to add three points calibration menu option. + // See http://minow.blogspot.com/index.html#4918805519571907051 + //#define DELTA_CALIBRATION_MENU + + // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) + //#define DELTA_AUTO_CALIBRATION + + // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them + + #if ENABLED(DELTA_AUTO_CALIBRATION) + // set the default number of probe points : n*n (1 -> 7) + #define DELTA_CALIBRATION_DEFAULT_POINTS 4 + #endif + + #if EITHER(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU) + // Set the steprate for papertest probing + #define PROBE_MANUALLY_STEP 0.05 // (mm) + #endif + + // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). + #define DELTA_PRINTABLE_RADIUS 140.0 // (mm) + + // Maximum reachable area + #define DELTA_MAX_RADIUS 140.0 // (mm) + + // Center-to-center distance of the holes in the diagonal push rods. + #define DELTA_DIAGONAL_ROD 250.0 // (mm) + + // Distance between bed and nozzle Z home position + #define DELTA_HEIGHT 250.00 // (mm) Get this value from G33 auto calibrate + + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate + + // Horizontal distance bridged by diagonal push rods when effector is centered. + #define DELTA_RADIUS 124.0 // (mm) Get this value from G33 auto calibrate + + // Trim adjustments for individual towers + // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 + // measured in degrees anticlockwise looking from above the printer + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate + + // Delta radius and diagonal rod adjustments (mm) + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } +#endif + +/** + * MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013. + * Implemented and slightly reworked by JCERNY in June, 2014. + * + * Mostly Printed SCARA is an open source design by Tyler Williams. See: + * https://www.thingiverse.com/thing:2487048 + * https://www.thingiverse.com/thing:1241491 + */ +//#define MORGAN_SCARA +//#define MP_SCARA +#if EITHER(MORGAN_SCARA, MP_SCARA) + // If movement is choppy try lowering this value + #define SCARA_SEGMENTS_PER_SECOND 200 + + // Length of inner and outer support arms. Measure arm lengths precisely. + #define SCARA_LINKAGE_1 150 // (mm) + #define SCARA_LINKAGE_2 150 // (mm) + + // SCARA tower offset (position of Tower relative to bed zero position) + // This needs to be reasonably accurate as it defines the printbed position in the SCARA space. + #define SCARA_OFFSET_X 100 // (mm) + #define SCARA_OFFSET_Y -56 // (mm) + + #if ENABLED(MORGAN_SCARA) + + //#define DEBUG_SCARA_KINEMATICS + #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly + + // Radius around the center where the arm cannot reach + #define MIDDLE_DEAD_ZONE_R 0 // (mm) + + #define THETA_HOMING_OFFSET 0 // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 + #define PSI_HOMING_OFFSET 0 // Calculated from Calibration Guide and M364 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 + + #elif ENABLED(MP_SCARA) + + #define SCARA_OFFSET_THETA1 12 // degrees + #define SCARA_OFFSET_THETA2 131 // degrees + + #endif + +#endif + +// Enable for TPARA kinematics and configure below +//#define AXEL_TPARA +#if ENABLED(AXEL_TPARA) + #define DEBUG_ROBOT_KINEMATICS + #define ROBOT_SEGMENTS_PER_SECOND 200 + + // Length of inner and outer support arms. Measure arm lengths precisely. + #define ROBOT_LINKAGE_1 120 // (mm) + #define ROBOT_LINKAGE_2 120 // (mm) + + // SCARA tower offset (position of Tower relative to bed zero position) + // This needs to be reasonably accurate as it defines the printbed position in the SCARA space. + #define ROBOT_OFFSET_X 0 // (mm) + #define ROBOT_OFFSET_Y 0 // (mm) + #define ROBOT_OFFSET_Z 0 // (mm) + + #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly + + // Radius around the center where the arm cannot reach + #define MIDDLE_DEAD_ZONE_R 0 // (mm) + + // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 + #define THETA_HOMING_OFFSET 0 + #define PSI_HOMING_OFFSET 0 +#endif + +// Articulated robot (arm). Joints are directly mapped to axes with no kinematics. +//#define ARTICULATED_ROBOT_ARM + +// For a hot wire cutter with parallel horizontal axes (X, I) where the heights of the two wire +// ends are controlled by parallel axes (Y, J). Joints are directly mapped to axes (no kinematics). +//#define FOAMCUTTER_XYUV + //=========================================================================== //============================== Endstop Settings =========================== //=========================================================================== @@ -941,47 +1090,6 @@ #define W_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. -/** - * Stepper Drivers - * - * These settings allow Marlin to tune stepper driver timing and enable advanced options for - * stepper drivers that support them. You may also override timing options in Configuration_adv.h. - * - * A4988 is assumed for unspecified drivers. - * - * Use TMC2208/TMC2208_STANDALONE for TMC2225 drivers and TMC2209/TMC2209_STANDALONE for TMC2226 drivers. - * - * Options: A4988, A5984, DRV8825, LV8729, L6470, L6474, POWERSTEP01, - * TB6560, TB6600, TMC2100, - * TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE, - * TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE, - * TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE, - * TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE - * :['A4988', 'A5984', 'DRV8825', 'LV8729', 'L6470', 'L6474', 'POWERSTEP01', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] - */ -#define X_DRIVER_TYPE A4988 -#define Y_DRIVER_TYPE A4988 -#define Z_DRIVER_TYPE A4988 -//#define X2_DRIVER_TYPE A4988 -//#define Y2_DRIVER_TYPE A4988 -//#define Z2_DRIVER_TYPE A4988 -//#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 U_DRIVER_TYPE A4988 -//#define V_DRIVER_TYPE A4988 -//#define W_DRIVER_TYPE A4988 -#define E0_DRIVER_TYPE A4988 -//#define E1_DRIVER_TYPE A4988 -//#define E2_DRIVER_TYPE A4988 -//#define E3_DRIVER_TYPE A4988 -//#define E4_DRIVER_TYPE A4988 -//#define E5_DRIVER_TYPE A4988 -//#define E6_DRIVER_TYPE A4988 -//#define E7_DRIVER_TYPE A4988 - // Enable this feature if all enabled endstop pins are interrupt-capable. // This will remove the need to poll the interrupt pins, saving many CPU cycles. //#define ENDSTOP_INTERRUPTS_FEATURE @@ -1235,6 +1343,27 @@ #define Z_PROBE_RETRACT_X X_MAX_POS #endif +/** + * Magnetically Mounted Probe + * For probes such as Euclid, Klicky, Klackender, etc. + */ +//#define MAG_MOUNTED_PROBE +#if ENABLED(MAG_MOUNTED_PROBE) + #define PROBE_DEPLOY_FEEDRATE (133*60) // (mm/min) Probe deploy speed + #define PROBE_STOW_FEEDRATE (133*60) // (mm/min) Probe stow speed + + #define MAG_MOUNTED_DEPLOY_1 { PROBE_DEPLOY_FEEDRATE, { 245, 114, 30 } } // Move to side Dock & Attach probe + #define MAG_MOUNTED_DEPLOY_2 { PROBE_DEPLOY_FEEDRATE, { 210, 114, 30 } } // Move probe off dock + #define MAG_MOUNTED_DEPLOY_3 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed + #define MAG_MOUNTED_DEPLOY_4 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed + #define MAG_MOUNTED_DEPLOY_5 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed + #define MAG_MOUNTED_STOW_1 { PROBE_STOW_FEEDRATE, { 245, 114, 20 } } // Move to dock + #define MAG_MOUNTED_STOW_2 { PROBE_STOW_FEEDRATE, { 245, 114, 0 } } // Place probe beside remover + #define MAG_MOUNTED_STOW_3 { PROBE_STOW_FEEDRATE, { 230, 114, 0 } } // Side move to remove probe + #define MAG_MOUNTED_STOW_4 { PROBE_STOW_FEEDRATE, { 210, 114, 20 } } // Side move to remove probe + #define MAG_MOUNTED_STOW_5 { PROBE_STOW_FEEDRATE, { 0, 0, 0 } } // Extra move if needed +#endif + // Duet Smart Effector (for delta printers) - https://bit.ly/2ul5U7J // When the pin is defined you can use M672 to set/reset the probe sensitivity. //#define DUET_SMART_EFFECTOR @@ -1250,9 +1379,37 @@ */ //#define SENSORLESS_PROBING -// -// For Z_PROBE_ALLEN_KEY see the Delta example configurations. -// +/** + * Allen key retractable z-probe as seen on many Kossel delta printers - https://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe + * Deploys by touching z-axis belt. Retracts by pushing the probe down. + */ +//#define Z_PROBE_ALLEN_KEY +#if ENABLED(Z_PROBE_ALLEN_KEY) + // 2 or 3 sets of coordinates for deploying and retracting the spring loaded touch probe on G29, + // if servo actuated touch probe is not defined. Uncomment as appropriate for your printer/probe. + + #define Z_PROBE_ALLEN_KEY_DEPLOY_1 { 30.0, DELTA_PRINTABLE_RADIUS, 100.0 } + #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE XY_PROBE_FEEDRATE + + #define Z_PROBE_ALLEN_KEY_DEPLOY_2 { 0.0, DELTA_PRINTABLE_RADIUS, 100.0 } + #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE (XY_PROBE_FEEDRATE)/10 + + #define Z_PROBE_ALLEN_KEY_DEPLOY_3 { 0.0, (DELTA_PRINTABLE_RADIUS) * 0.75, 100.0 } + #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE XY_PROBE_FEEDRATE + + #define Z_PROBE_ALLEN_KEY_STOW_1 { -64.0, 56.0, 23.0 } // Move the probe into position + #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE XY_PROBE_FEEDRATE + + #define Z_PROBE_ALLEN_KEY_STOW_2 { -64.0, 56.0, 3.0 } // Push it down + #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE (XY_PROBE_FEEDRATE)/10 + + #define Z_PROBE_ALLEN_KEY_STOW_3 { -64.0, 56.0, 50.0 } // Move it up to clear + #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE XY_PROBE_FEEDRATE + + #define Z_PROBE_ALLEN_KEY_STOW_4 { 0.0, 0.0, 50.0 } + #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE XY_PROBE_FEEDRATE + +#endif // Z_PROBE_ALLEN_KEY /** * Nozzle-to-Probe offsets { X, Y, Z } @@ -1824,18 +1981,18 @@ #endif // Add a menu item to move between bed corners for manual bed adjustment -//#define LEVEL_BED_CORNERS - -#if ENABLED(LEVEL_BED_CORNERS) - #define LEVEL_CORNERS_INSET_LFRB { 30, 30, 30, 30 } // (mm) Left, Front, Right, Back insets - #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 +//#define LCD_BED_TRAMMING + +#if ENABLED(LCD_BED_TRAMMING) + #define BED_TRAMMING_INSET_LFRB { 30, 30, 30, 30 } // (mm) Left, Front, Right, Back insets + #define BED_TRAMMING_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points + #define BED_TRAMMING_Z_HOP 4.0 // (mm) Z height of nozzle between leveling points + //#define BED_TRAMMING_INCLUDE_CENTER // Move to the center after the last corner + //#define BED_TRAMMING_USE_PROBE + #if ENABLED(BED_TRAMMING_USE_PROBE) + #define BED_TRAMMING_PROBE_TOLERANCE 0.1 // (mm) + #define BED_TRAMMING_VERIFY_RAISED // After adjustment triggers the probe, re-probe to verify + //#define BED_TRAMMING_AUDIO_FEEDBACK #endif /** @@ -1855,7 +2012,7 @@ * | 1 2 | | 1 4 | | 1 2 | | 2 | * LF --------- RF LF --------- RF LF --------- RF LF --------- RF */ - #define LEVEL_CORNERS_LEVELING_ORDER { LF, RF, RB, LB } + #define BED_TRAMMING_LEVELING_ORDER { LF, RF, RB, LB } #endif /** @@ -2642,6 +2799,12 @@ // //#define SILVER_GATE_GLCD_CONTROLLER +// +// eMotion Tech LCD with SD +// https://www.reprap-france.com/produit/1234568748-ecran-graphique-128-x-64-points-2-1 +// +//#define EMOTION_TECH_LCD + //============================================================================= //============================== OLED Displays ============================== //============================================================================= @@ -2750,9 +2913,6 @@ // Touch-screen LCD for Malyan M200/M300 printers // //#define MALYAN_LCD -#if ENABLED(MALYAN_LCD) - #define LCD_SERIAL_PORT 1 // Default is 1 for Malyan M200 -#endif // // Touch UI for FTDI EVE (FT800/FT810) displays @@ -2766,7 +2926,6 @@ //#define ANYCUBIC_LCD_I3MEGA //#define ANYCUBIC_LCD_CHIRON #if EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) - #define LCD_SERIAL_PORT 3 // Default is 3 for Anycubic //#define ANYCUBIC_LCD_DEBUG #endif @@ -2774,9 +2933,6 @@ // 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. @@ -2929,7 +3085,6 @@ // //#define DWIN_CREALITY_LCD // Creality UI //#define DWIN_LCD_PROUI // Pro UI by MRiscoC -//#define DWIN_CREALITY_LCD_JYERSUI // Jyers UI by Jacob Myers //#define DWIN_MARLINUI_PORTRAIT // MarlinUI (portrait orientation) //#define DWIN_MARLINUI_LANDSCAPE // MarlinUI (landscape orientation) @@ -3051,7 +3206,8 @@ // Support for Adafruit NeoPixel LED driver //#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_TYPE NEO_GRBW // NEO_GRBW, NEO_RGBW, NEO_GRB, NEO_RBG, etc. + // See https://github.com/adafruit/Adafruit_NeoPixel/blob/master/Adafruit_NeoPixel.h //#define NEOPIXEL_PIN 4 // LED driving pin //#define NEOPIXEL2_TYPE NEOPIXEL_TYPE //#define NEOPIXEL2_PIN 5 diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7ec7ed40a7f9..7f85b241a2ea 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 02010000 +#define CONFIGURATION_ADV_H_VERSION 02010100 //=========================================================================== //============================= Thermal Settings ============================ @@ -249,20 +249,6 @@ #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 @@ -713,73 +699,6 @@ //#define CLOSED_LOOP_MOVE_COMPLETE_PIN -1 #endif -/** - * Dual Steppers / Dual Endstops - * - * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes. - * - * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to - * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop - * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug - * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'. - * - * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors - * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error - * in X2. Dual endstop offsets can be set at runtime with 'M666 X Y Z'. - */ - -//#define X_DUAL_STEPPER_DRIVERS -#if ENABLED(X_DUAL_STEPPER_DRIVERS) - //#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_ - #define X2_ENDSTOP_ADJUSTMENT 0 - #endif -#endif - -//#define Y_DUAL_STEPPER_DRIVERS -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) - //#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_ - #define Y2_ENDSTOP_ADJUSTMENT 0 - #endif -#endif - -// -// For Z set the number of stepper drivers -// -#define NUM_Z_STEPPER_DRIVERS 1 // (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_ - #define Z2_ENDSTOP_ADJUSTMENT 0 - #if NUM_Z_STEPPER_DRIVERS >= 3 - #define Z3_USE_ENDSTOP _YMAX_ - #define Z3_ENDSTOP_ADJUSTMENT 0 - #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 - #define Z4_USE_ENDSTOP _ZMAX_ - #define Z4_ENDSTOP_ADJUSTMENT 0 - #endif - #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 * @@ -830,6 +749,77 @@ //#define EVENT_GCODE_IDEX_AFTER_MODECHANGE "G28X" #endif +/** + * Multi-Stepper / Multi-Endstop + * + * When X2_DRIVER_TYPE is defined, this indicates that the X and X2 motors work in tandem. + * The following explanations for X also apply to Y and Z multi-stepper setups. + * Endstop offsets may be changed by 'M666 X Y Z' and stored to EEPROM. + * + * - Enable INVERT_X2_VS_X_DIR if the X2 motor requires an opposite DIR signal from X. + * + * - Enable X_DUAL_ENDSTOPS if the second motor has its own endstop, with adjustable offset. + * + * - Extra endstops are included in the output of 'M119'. + * + * - Set X_DUAL_ENDSTOP_ADJUSTMENT to the known error in the X2 endstop. + * Applied to the X2 motor on 'G28' / 'G28 X'. + * Get the offset by homing X and measuring the error. + * Also set with 'M666 X' and stored to EEPROM with 'M500'. + * + * - Use X2_USE_ENDSTOP to set the endstop plug by name. (_XMIN_, _XMAX_, _YMIN_, _YMAX_, _ZMIN_, _ZMAX_) + */ +#if HAS_X2_STEPPER && DISABLED(DUAL_X_CARRIAGE) + //#define INVERT_X2_VS_X_DIR // X2 direction signal is the opposite of X + //#define X_DUAL_ENDSTOPS // X2 has its own endstop + #if ENABLED(X_DUAL_ENDSTOPS) + #define X2_USE_ENDSTOP _XMAX_ // X2 endstop board plug. Don't forget to enable USE_*_PLUG. + #define X2_ENDSTOP_ADJUSTMENT 0 // X2 offset relative to X endstop + #endif +#endif + +#if HAS_DUAL_Y_STEPPERS + //#define INVERT_Y2_VS_Y_DIR // Y2 direction signal is the opposite of Y + //#define Y_DUAL_ENDSTOPS // Y2 has its own endstop + #if ENABLED(Y_DUAL_ENDSTOPS) + #define Y2_USE_ENDSTOP _YMAX_ // Y2 endstop board plug. Don't forget to enable USE_*_PLUG. + #define Y2_ENDSTOP_ADJUSTMENT 0 // Y2 offset relative to Y endstop + #endif +#endif + +// +// Multi-Z steppers +// +#ifdef Z2_DRIVER_TYPE + //#define INVERT_Z2_VS_Z_DIR // Z2 direction signal is the opposite of Z + + //#define Z_MULTI_ENDSTOPS // Other Z axes have their own endstops + #if ENABLED(Z_MULTI_ENDSTOPS) + #define Z2_USE_ENDSTOP _XMAX_ // Z2 endstop board plug. Don't forget to enable USE_*_PLUG. + #define Z2_ENDSTOP_ADJUSTMENT 0 // Z2 offset relative to Y endstop + #endif + #ifdef Z3_DRIVER_TYPE + //#define INVERT_Z3_VS_Z_DIR // Z3 direction signal is the opposite of Z + #if ENABLED(Z_MULTI_ENDSTOPS) + #define Z3_USE_ENDSTOP _YMAX_ // Z3 endstop board plug. Don't forget to enable USE_*_PLUG. + #define Z3_ENDSTOP_ADJUSTMENT 0 // Z3 offset relative to Y endstop + #endif + #endif + #ifdef Z4_DRIVER_TYPE + //#define INVERT_Z4_VS_Z_DIR // Z4 direction signal is the opposite of Z + #if ENABLED(Z_MULTI_ENDSTOPS) + #define Z4_USE_ENDSTOP _ZMAX_ // Z4 endstop board plug. Don't forget to enable USE_*_PLUG. + #define Z4_ENDSTOP_ADJUSTMENT 0 // Z4 offset relative to Y endstop + #endif + #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 // E direction signals are opposites +#endif + // Activate a solenoid on the active extruder with M380. Disable all with M381. // Define SOL0_PIN, SOL1_PIN, etc., for each extruder that has a solenoid. //#define EXT_SOLENOID @@ -963,7 +953,7 @@ /** * Z Stepper positions for more rapid convergence in bed alignment. - * Requires NUM_Z_STEPPER_DRIVERS to be 3 or 4. + * Requires 3 or 4 Z steppers. * * Define Stepper XY positions for Z1, Z2, Z3... corresponding to the screw * positions in the bed carriage, with one position per Z stepper in stepper @@ -1329,6 +1319,9 @@ #define XATC_Y_POSITION Y_CENTER // (mm) Y position to probe #define XATC_Z_OFFSETS { 0, 0, 0 } // Z offsets for X axis sample points #endif + + // Show Deploy / Stow Probe options in the Motion menu. + #define PROBE_DEPLOY_STOW_MENU #endif // Include a page of printer information in the LCD Main Menu @@ -1345,8 +1338,9 @@ #endif // HAS_MARLINUI_MENU -#if ANY(HAS_DISPLAY, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) +#if EITHER(HAS_DISPLAY, DWIN_LCD_PROUI) //#define SOUND_MENU_ITEM // Add a mute option to the LCD menu + #define SOUND_ON_DEFAULT // Buzzer/speaker default enabled state #endif #if EITHER(HAS_DISPLAY, DWIN_LCD_PROUI) @@ -1688,11 +1682,11 @@ //#define XYZ_NO_FRAME #define XYZ_HOLLOW_FRAME - // A bigger font is available for edit items. Costs 3120 bytes of PROGMEM. + // A bigger font is available for edit items. Costs 3120 bytes of flash. // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_BIG_EDIT_FONT - // A smaller font may be used on the Info Screen. Costs 2434 bytes of PROGMEM. + // A smaller font may be used on the Info Screen. Costs 2434 bytes of flash. // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_SMALL_INFOFONT @@ -1748,7 +1742,7 @@ //#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap //#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames //#define STATUS_HEAT_PERCENT // Show heating in a progress bar - //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of PROGMEM. + //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of flash. // Frivolous Game Options //#define MARLIN_BRICKOUT @@ -1773,7 +1767,6 @@ // Additional options for DGUS / DWIN displays // #if HAS_DGUS_LCD - #define LCD_SERIAL_PORT 3 #define LCD_BAUDRATE 115200 #define DGUS_RX_BUFFER_SIZE 128 @@ -2309,7 +2302,7 @@ #define BUFSIZE 4 // Transmission to Host Buffer Size -// To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0. +// To save 386 bytes of flash (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0. // To buffer a simple "ok" you need 4 bytes. // For ADVANCED_OK (M105) you need 32 bytes. // For debug-echo: 128 bytes for the optimal speed. @@ -2460,7 +2453,7 @@ /** * Extra G-code to run while executing tool-change commands. Can be used to use an additional - * stepper motor (I axis, see option NUM_AXES in Configuration.h) to drive the tool-changer. + * stepper motor (e.g., I axis in Configuration.h) to drive the tool-changer. */ //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 @@ -3602,6 +3595,9 @@ #if ENABLED(SPINDLE_LASER_USE_PWM) #define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR, ESP32, and LPC) + // ESP32: If SPINDLE_LASER_PWM_PIN is onboard then <=78125Hz. For I2S expander + // the frequency determines the PWM resolution. 2500Hz = 0-100, 977Hz = 0-255, ... + // (250000 / SPINDLE_LASER_FREQUENCY) = max value. #endif //#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11 @@ -3675,83 +3671,55 @@ #endif // 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 + #define LASER_TEST_PULSE_MIN 1 // (ms) Used with Laser Control Menu + #define LASER_TEST_PULSE_MAX 999 // (ms) Caution: Menu may not show more than 3 characters + + #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop + + /** + * Laser Safety Timeout + * + * The laser should be turned off when there is no movement for a period of time. + * Consider material flammability, cut rate, and G-code order when setting this + * value. Too low and it could turn off during a very slow move; too high and + * the material could ignite. + */ + #define LASER_SAFETY_TIMEOUT_MS 1000 // (ms) /** - * Enable inline laser power to be handled in the planner / stepper routines. - * Inline power is specified by the I (inline) flag in an M3 command (e.g., M3 S20 I) - * or by the 'S' parameter in G0/G1/G2/G3 moves (see LASER_MOVE_POWER). + * Any M3 or G1/2/3/5 command with the 'I' parameter enables continuous inline power mode. + * + * e.g., 'M3 I' enables continuous inline power which is processed by the planner. + * Power is stored in move blocks and applied when blocks are processed by the Stepper ISR. + * + * 'M4 I' sets dynamic mode which uses the current feedrate to calculate a laser power OCR value. * - * This allows the laser to keep in perfect sync with the planner and removes - * the powerup/down delay since lasers require negligible time. + * Any move in dynamic mode will use the current feedrate to calculate the laser power. + * Feed rates are set by the F parameter of a move command e.g. G1 X0 Y10 F6000 + * Laser power would be calculated by bit shifting off 8 LSB's. In binary this is div 256. + * The calculation gives us ocr values from 0 to 255, values over F65535 will be set as 255 . + * More refined power control such as compesation for accell/decell will be addressed in future releases. + * + * M5 I clears inline mode and set power to 0, M5 sets the power output to 0 but leaves inline mode on. */ - //#define LASER_POWER_INLINE - - #if ENABLED(LASER_POWER_INLINE) - /** - * Scale the laser's power in proportion to the movement rate. - * - * - Sets the entry power proportional to the entry speed over the nominal speed. - * - Ramps the power up every N steps to approximate the speed trapezoid. - * - Due to the limited power resolution this is only approximate. - */ - #define LASER_POWER_INLINE_TRAPEZOID - - /** - * Continuously calculate the current power (nominal_power * current_rate / nominal_rate). - * Required for accurate power with non-trapezoidal acceleration (e.g., S_CURVE_ACCELERATION). - * This is a costly calculation so this option is discouraged on 8-bit AVR boards. - * - * LASER_POWER_INLINE_TRAPEZOID_CONT_PER defines how many step cycles there are between power updates. If your - * board isn't able to generate steps fast enough (and you are using LASER_POWER_INLINE_TRAPEZOID_CONT), increase this. - * Note that when this is zero it means it occurs every cycle; 1 means a delay wait one cycle then run, etc. - */ - //#define LASER_POWER_INLINE_TRAPEZOID_CONT - - /** - * Stepper iterations between power updates. Increase this value if the board - * can't keep up with the processing demands of LASER_POWER_INLINE_TRAPEZOID_CONT. - * Disable (or set to 0) to recalculate power on every stepper iteration. - */ - //#define LASER_POWER_INLINE_TRAPEZOID_CONT_PER 10 - - /** - * Include laser power in G0/G1/G2/G3/G5 commands with the 'S' parameter - */ - //#define LASER_MOVE_POWER - - #if ENABLED(LASER_MOVE_POWER) - // Turn off the laser on G0 moves with no power parameter. - // If a power parameter is provided, use that instead. - //#define LASER_MOVE_G0_OFF - - // Turn off the laser on G28 homing. - //#define LASER_MOVE_G28_OFF - #endif - - /** - * Inline flag inverted - * - * WARNING: M5 will NOT turn off the laser unless another move - * is done (so G-code files must end with 'M5 I'). - */ - //#define LASER_POWER_INLINE_INVERT - - /** - * Continuously apply inline power. ('M3 S3' == 'G1 S3' == 'M3 S3 I') - * - * The laser might do some weird things, so only enable this - * feature if you understand the implications. - */ - //#define LASER_POWER_INLINE_CONTINUOUS - #else - - #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power - #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop + /** + * Enable M3 commands for laser mode inline power planner syncing. + * This feature enables any M3 S-value to be injected into the block buffers while in + * CUTTER_MODE_CONTINUOUS. The option allows M3 laser power to be commited without waiting + * for a planner syncronization + */ + //#define LASER_POWER_SYNC - #endif + /** + * Scale the laser's power in proportion to the movement rate. + * + * - Sets the entry power proportional to the entry speed over the nominal speed. + * - Ramps the power up every N steps to approximate the speed trapezoid. + * - Due to the limited power resolution this is only approximate. + */ + //#define LASER_POWER_TRAP // // Laser I2C Ammeter (High precision INA226 low/high side module) @@ -3762,6 +3730,20 @@ #define I2C_AMMETER_SHUNT_RESISTOR 0.1 // (Ohms) Calibration shunt resistor value #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 + #endif #endif // SPINDLE_FEATURE || LASER_FEATURE @@ -4272,7 +4254,8 @@ #define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain. #define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°) // connector at: right=0 bottom=-90 top=90 left=180 - //#define MAX7219_REVERSE_ORDER // The individual LED matrix units may be in reversed order + //#define MAX7219_REVERSE_ORDER // The order of the LED matrix units may be reversed + //#define MAX7219_REVERSE_EACH // The LEDs in each matrix unit row may be reversed //#define MAX7219_SIDE_BY_SIDE // Big chip+matrix boards can be chained side-by-side /** @@ -4280,12 +4263,15 @@ * If you add more debug displays, be careful to avoid conflicts! */ #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning - #define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row - #define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row + #define MAX7219_DEBUG_PLANNER_HEAD 2 // Show the planner queue head position on this and the next LED matrix row + #define MAX7219_DEBUG_PLANNER_TAIL 4 // Show the planner queue tail position on this and the next LED matrix row #define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row // If you experience stuttering, reboots, etc. this option can reveal how // tweaks made to the configuration are affecting the printer in real-time. + #define MAX7219_DEBUG_PROFILE 6 // Display the fraction of CPU time spent in profiled code on this LED matrix + // row. By default idle() is profiled so this shows how "idle" the processor is. + // See class CodeProfiler. #endif /** diff --git a/Marlin/Makefile b/Marlin/Makefile index f1c89ff7f520..563354fdbe1f 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -109,7 +109,7 @@ LIQUID_TWI2 ?= 0 # This defines if Wire is needed WIRE ?= 0 -# This defines if Tone is needed (i.e SPEAKER is defined in Configuration.h) +# This defines if Tone is needed (i.e., SPEAKER is defined in Configuration.h) # Disabling this (and SPEAKER) saves approximately 350 bytes of memory. TONE ?= 1 @@ -512,7 +512,7 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1324) else ifeq ($(HARDWARE_MOTHERBOARD),1325) # Intamsys 4.0 (Funmat HT) else ifeq ($(HARDWARE_MOTHERBOARD),1326) -# Malyan M180 Mainboard Version 2 (no display function, direct gcode only) +# Malyan M180 Mainboard Version 2 (no display function, direct G-code only) else ifeq ($(HARDWARE_MOTHERBOARD),1327) # Geeetech GT2560 Rev B for A20(M/T/D) else ifeq ($(HARDWARE_MOTHERBOARD),1328) diff --git a/Marlin/Version.h b/Marlin/Version.h index 12a67a2461e9..0c966a2f3846 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "bugfix-2.0.x" +//#define SHORT_BUILD_VERSION "bugfix-2.1.x" /** * 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 "2022-04-24" +//#define STRING_DISTRIBUTION_DATE "2022-07-07" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 7c39c5200b4d..5382eb36a2bd 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -23,6 +23,7 @@ #include "../../inc/MarlinConfig.h" #include "HAL.h" +#include #ifdef USBCON DefaultSerial1 MSerial0(false, Serial); @@ -88,6 +89,62 @@ void MarlinHAL::reboot() { #endif } +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + #include + #include "../../MarlinCore.h" + + // Initialize watchdog with 8s timeout, if possible. Otherwise, make it 4s. + void MarlinHAL::watchdog_init() { + #if ENABLED(WATCHDOG_DURATION_8S) && defined(WDTO_8S) + #define WDTO_NS WDTO_8S + #else + #define WDTO_NS WDTO_4S + #endif + #if ENABLED(WATCHDOG_RESET_MANUAL) + // Enable the watchdog timer, but only for the interrupt. + // Take care, as this requires the correct order of operation, with interrupts disabled. + // See the datasheet of any AVR chip for details. + wdt_reset(); + cli(); + _WD_CONTROL_REG = _BV(_WD_CHANGE_BIT) | _BV(WDE); + _WD_CONTROL_REG = _BV(WDIE) | (WDTO_NS & 0x07) | ((WDTO_NS & 0x08) << 2); // WDTO_NS directly does not work. bit 0-2 are consecutive in the register but the highest value bit is at bit 5 + // So worked for up to WDTO_2S + sei(); + wdt_reset(); + #else + wdt_enable(WDTO_NS); // The function handles the upper bit correct. + #endif + //delay(10000); // test it! + } + + //=========================================================================== + //=================================== ISR =================================== + //=========================================================================== + + // Watchdog timer interrupt, called if main program blocks >4sec and manual reset is enabled. + #if ENABLED(WATCHDOG_RESET_MANUAL) + ISR(WDT_vect) { + sei(); // With the interrupt driven serial we need to allow interrupts. + SERIAL_ERROR_MSG(STR_WATCHDOG_FIRED); + minkill(); // interrupt-safe final kill and infinite loop + } + #endif + + // Reset watchdog. MUST be called at least every 4 seconds after the + // first watchdog_init or AVR will go into emergency procedures. + void MarlinHAL::watchdog_refresh() { wdt_reset(); } + +#endif // USE_WATCHDOG + +// ------------------------ +// Free Memory Accessor +// ------------------------ + #if ENABLED(SDSUPPORT) #include "../../sd/SdFatUtil.h" diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index a2062775c424..149186772158 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -26,13 +26,11 @@ #include "../shared/Marduino.h" #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include "math.h" #ifdef USBCON #include #else - #define HardwareSerial_h // Hack to prevent HardwareSerial.h header inclusion #include "MarlinSerial.h" #endif @@ -168,7 +166,7 @@ typedef Servo hal_servo_t; #define strtof strtod // ------------------------ -// Class Utilities +// Free Memory Accessor // ------------------------ #pragma GCC diagnostic push @@ -190,6 +188,10 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static void init(); // Called early in setup() static void init_board() {} // Called less early in setup() static void reboot(); // Restart the firmware from 0x0 diff --git a/Marlin/src/HAL/AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp index 526352b77339..0a1ef5337ae9 100644 --- a/Marlin/src/HAL/AVR/Servo.cpp +++ b/Marlin/src/HAL/AVR/Servo.cpp @@ -66,27 +66,26 @@ static volatile int8_t Channel[_Nbr_16timers]; // counter for the s /************ static functions common to all instances ***********************/ -static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t* TCNTn, volatile uint16_t* OCRnA) { - if (Channel[timer] < 0) - *TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer - else { - if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive) - extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated - } - - Channel[timer]++; // increment to the next channel - if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) { - *OCRnA = *TCNTn + SERVO(timer, Channel[timer]).ticks; - if (SERVO(timer, Channel[timer]).Pin.isActive) // check if activated - extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high +static inline void handle_interrupts(const timer16_Sequence_t timer, volatile uint16_t* TCNTn, volatile uint16_t* OCRnA) { + int8_t cho = Channel[timer]; // Handle the prior Channel[timer] first + if (cho < 0) // Channel -1 indicates the refresh interval completed... + *TCNTn = 0; // ...so reset the timer + else if (SERVO_INDEX(timer, cho) < ServoCount) // prior channel handled? + extDigitalWrite(SERVO(timer, cho).Pin.nbr, LOW); // pulse the prior channel LOW + + Channel[timer] = ++cho; // Handle the next channel (or 0) + if (cho < SERVOS_PER_TIMER && SERVO_INDEX(timer, cho) < ServoCount) { + *OCRnA = *TCNTn + SERVO(timer, cho).ticks; // set compare to current ticks plus duration + if (SERVO(timer, cho).Pin.isActive) // activated? + extDigitalWrite(SERVO(timer, cho).Pin.nbr, HIGH); // yes: pulse HIGH } else { // finished all channels so wait for the refresh period to expire before starting over - if (((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL)) // allow a few ticks to ensure the next OCR1A not missed - *OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL); - else - *OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed - Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel + const unsigned int cval = ((unsigned)*TCNTn) + 32 / (SERVO_TIMER_PRESCALER), // allow 32 cycles to ensure the next OCR1A not missed + ival = (unsigned int)usToTicks(REFRESH_INTERVAL); // at least REFRESH_INTERVAL has elapsed + *OCRnA = max(cval, ival); + + Channel[timer] = -1; // reset the timer counter to 0 on the next call } } @@ -123,91 +122,102 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t /****************** end of static functions ******************************/ -void initISR(timer16_Sequence_t timer) { - #ifdef _useTimer1 - if (timer == _timer1) { - TCCR1A = 0; // normal counting mode - TCCR1B = _BV(CS11); // set prescaler of 8 - TCNT1 = 0; // clear the timer count - #if defined(__AVR_ATmega8__) || defined(__AVR_ATmega128__) - SBI(TIFR, OCF1A); // clear any pending interrupts; - SBI(TIMSK, OCIE1A); // enable the output compare interrupt - #else - // here if not ATmega8 or ATmega128 - SBI(TIFR1, OCF1A); // clear any pending interrupts; - SBI(TIMSK1, OCIE1A); // enable the output compare interrupt - #endif - #ifdef WIRING - timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service); - #endif - } - #endif - - #ifdef _useTimer3 - if (timer == _timer3) { - TCCR3A = 0; // normal counting mode - TCCR3B = _BV(CS31); // set prescaler of 8 - TCNT3 = 0; // clear the timer count - #ifdef __AVR_ATmega128__ - SBI(TIFR, OCF3A); // clear any pending interrupts; - SBI(ETIMSK, OCIE3A); // enable the output compare interrupt - #else - SBI(TIFR3, OCF3A); // clear any pending interrupts; - SBI(TIMSK3, OCIE3A); // enable the output compare interrupt - #endif - #ifdef WIRING - timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only - #endif - } - #endif - - #ifdef _useTimer4 - if (timer == _timer4) { - TCCR4A = 0; // normal counting mode - TCCR4B = _BV(CS41); // set prescaler of 8 - TCNT4 = 0; // clear the timer count - TIFR4 = _BV(OCF4A); // clear any pending interrupts; - TIMSK4 = _BV(OCIE4A); // enable the output compare interrupt - } - #endif - - #ifdef _useTimer5 - if (timer == _timer5) { - TCCR5A = 0; // normal counting mode - TCCR5B = _BV(CS51); // set prescaler of 8 - TCNT5 = 0; // clear the timer count - TIFR5 = _BV(OCF5A); // clear any pending interrupts; - TIMSK5 = _BV(OCIE5A); // enable the output compare interrupt - } - #endif -} - -void finISR(timer16_Sequence_t timer) { - // Disable use of the given timer - #ifdef WIRING - if (timer == _timer1) { - CBI( - #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) - TIMSK1 +void initISR(const timer16_Sequence_t timer_index) { + switch (timer_index) { + default: break; + + #ifdef _useTimer1 + case _timer1: + TCCR1A = 0; // normal counting mode + TCCR1B = _BV(CS11); // set prescaler of 8 + TCNT1 = 0; // clear the timer count + #if defined(__AVR_ATmega8__) || defined(__AVR_ATmega128__) + SBI(TIFR, OCF1A); // clear any pending interrupts; + SBI(TIMSK, OCIE1A); // enable the output compare interrupt #else - TIMSK + // here if not ATmega8 or ATmega128 + SBI(TIFR1, OCF1A); // clear any pending interrupts; + SBI(TIMSK1, OCIE1A); // enable the output compare interrupt #endif - , OCIE1A); // disable timer 1 output compare interrupt - timerDetach(TIMER1OUTCOMPAREA_INT); - } - else if (timer == _timer3) { - CBI( - #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) - TIMSK3 + #ifdef WIRING + timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service); + #endif + break; + #endif + + #ifdef _useTimer3 + case _timer3: + TCCR3A = 0; // normal counting mode + TCCR3B = _BV(CS31); // set prescaler of 8 + TCNT3 = 0; // clear the timer count + #ifdef __AVR_ATmega128__ + SBI(TIFR, OCF3A); // clear any pending interrupts; + SBI(ETIMSK, OCIE3A); // enable the output compare interrupt #else - ETIMSK + SBI(TIFR3, OCF3A); // clear any pending interrupts; + SBI(TIMSK3, OCIE3A); // enable the output compare interrupt + #endif + #ifdef WIRING + timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only #endif - , OCIE3A); // disable the timer3 output compare A interrupt - timerDetach(TIMER3OUTCOMPAREA_INT); + break; + #endif + + #ifdef _useTimer4 + case _timer4: + TCCR4A = 0; // normal counting mode + TCCR4B = _BV(CS41); // set prescaler of 8 + TCNT4 = 0; // clear the timer count + TIFR4 = _BV(OCF4A); // clear any pending interrupts; + TIMSK4 = _BV(OCIE4A); // enable the output compare interrupt + break; + #endif + + #ifdef _useTimer5 + case _timer5: + TCCR5A = 0; // normal counting mode + TCCR5B = _BV(CS51); // set prescaler of 8 + TCNT5 = 0; // clear the timer count + TIFR5 = _BV(OCF5A); // clear any pending interrupts; + TIMSK5 = _BV(OCIE5A); // enable the output compare interrupt + break; + #endif + } +} + +void finISR(const timer16_Sequence_t timer_index) { + // Disable use of the given timer + #ifdef WIRING + switch (timer_index) { + default: break; + + case _timer1: + CBI( + #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) + TIMSK1 + #else + TIMSK + #endif + , OCIE1A // disable timer 1 output compare interrupt + ); + timerDetach(TIMER1OUTCOMPAREA_INT); + break; + + case _timer3: + CBI( + #if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) + TIMSK3 + #else + ETIMSK + #endif + , OCIE3A // disable the timer3 output compare A interrupt + ); + timerDetach(TIMER3OUTCOMPAREA_INT); + break; } #else // !WIRING // For arduino - in future: call here to a currently undefined function to reset the timer - UNUSED(timer); + UNUSED(timer_index); #endif } diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 15a5be4cd257..1c1d8d441351 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -25,6 +25,30 @@ * Test AVR-specific configuration values for errors at compile-time. */ +/** + * Check for common serial pin conflicts + */ +#define CHECK_SERIAL_PIN(N) ( \ + X_STOP_PIN == N || Y_STOP_PIN == N || Z_STOP_PIN == N \ + || X_MIN_PIN == N || Y_MIN_PIN == N || Z_MIN_PIN == N \ + || X_MAX_PIN == N || Y_MAX_PIN == N || Z_MAX_PIN == N \ + || X_STEP_PIN == N || Y_STEP_PIN == N || Z_STEP_PIN == N \ + || X_DIR_PIN == N || Y_DIR_PIN == N || Z_DIR_PIN == N \ + || X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \ +) +#if CONF_SERIAL_IS(0) // D0-D1. No known conflicts. +#endif +#if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19)) + #error "Serial Port 1 pin D18 and/or D19 conflicts with another pin on the board." +#endif +#if CONF_SERIAL_IS(2) && (CHECK_SERIAL_PIN(16) || CHECK_SERIAL_PIN(17)) + #error "Serial Port 2 pin D16 and/or D17 conflicts with another pin on the board." +#endif +#if CONF_SERIAL_IS(3) && (CHECK_SERIAL_PIN(14) || CHECK_SERIAL_PIN(15)) + #error "Serial Port 3 pin D14 and/or D15 conflicts with another pin on the board." +#endif +#undef CHECK_SERIAL_PIN + /** * Checks for FAST PWM */ diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index 247ae32b8fa7..dab4e4471524 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -74,7 +74,7 @@ #define MULTI_NAME_PAD 26 // space needed to be pretty if not first name assigned to a pin void PRINT_ARRAY_NAME(uint8_t x) { - char *name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name); + PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name); LOOP_L_N(y, MAX_NAME_LENGTH) { char temp_char = pgm_read_byte(name_mem_pointer + y); if (temp_char != 0) diff --git a/Marlin/src/HAL/AVR/watchdog.cpp b/Marlin/src/HAL/AVR/watchdog.cpp deleted file mode 100644 index 3f10c4adff81..000000000000 --- a/Marlin/src/HAL/AVR/watchdog.cpp +++ /dev/null @@ -1,70 +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 __AVR__ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#include "watchdog.h" - -#include "../../MarlinCore.h" - -// Initialize watchdog with 8s timeout, if possible. Otherwise, make it 4s. -void watchdog_init() { - #if ENABLED(WATCHDOG_DURATION_8S) && defined(WDTO_8S) - #define WDTO_NS WDTO_8S - #else - #define WDTO_NS WDTO_4S - #endif - #if ENABLED(WATCHDOG_RESET_MANUAL) - // Enable the watchdog timer, but only for the interrupt. - // Take care, as this requires the correct order of operation, with interrupts disabled. - // See the datasheet of any AVR chip for details. - wdt_reset(); - cli(); - _WD_CONTROL_REG = _BV(_WD_CHANGE_BIT) | _BV(WDE); - _WD_CONTROL_REG = _BV(WDIE) | (WDTO_NS & 0x07) | ((WDTO_NS & 0x08) << 2); // WDTO_NS directly does not work. bit 0-2 are consecutive in the register but the highest value bit is at bit 5 - // So worked for up to WDTO_2S - sei(); - wdt_reset(); - #else - wdt_enable(WDTO_NS); // The function handles the upper bit correct. - #endif - //delay(10000); // test it! -} - -//=========================================================================== -//=================================== ISR =================================== -//=========================================================================== - -// Watchdog timer interrupt, called if main program blocks >4sec and manual reset is enabled. -#if ENABLED(WATCHDOG_RESET_MANUAL) - ISR(WDT_vect) { - sei(); // With the interrupt driven serial we need to allow interrupts. - SERIAL_ERROR_MSG(STR_WATCHDOG_FIRED); - minkill(); // interrupt-safe final kill and infinite loop - } -#endif - -#endif // USE_WATCHDOG -#endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/watchdog.h b/Marlin/src/HAL/AVR/watchdog.h deleted file mode 100644 index a16c88b35e87..000000000000 --- a/Marlin/src/HAL/AVR/watchdog.h +++ /dev/null @@ -1,31 +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 - -// Initialize watchdog with a 4 second interrupt time -void watchdog_init(); - -// Reset watchdog. MUST be called at least every 4 seconds after the -// first watchdog_init or AVR will go into emergency procedures. -inline void HAL_watchdog_refresh() { wdt_reset(); } diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index bbd13dc05aac..4353f1649732 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -25,7 +25,7 @@ #ifdef ARDUINO_ARCH_SAM #include "../../inc/MarlinConfig.h" -#include "HAL.h" +#include "../../MarlinCore.h" #include #include "usb/usb_task.h" @@ -40,14 +40,15 @@ uint16_t MarlinHAL::adc_result; // Public functions // ------------------------ -TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); +#if ENABLED(POSTMORTEM_DEBUGGING) + extern void install_min_serial(); +#endif void MarlinHAL::init() { - // Initialize the USB stack #if ENABLED(SDSUPPORT) OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up #endif - usb_task_init(); + usb_task_init(); // Initialize the USB stack TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler } @@ -72,6 +73,103 @@ uint8_t MarlinHAL::get_reset_source() { void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); } +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + // Initialize watchdog - On SAM3X, Watchdog was already configured + // and enabled or disabled at startup, so no need to reconfigure it + // here. + void MarlinHAL::watchdog_init() { WDT_Restart(WDT); } // Reset watchdog to start clean + + // Reset watchdog. MUST be called at least every 4 seconds after the + // first watchdog_init or AVR will go into emergency procedures. + void MarlinHAL::watchdog_refresh() { watchdogReset(); } + +#endif + +// Override Arduino runtime to either config or disable the watchdog +// +// We need to configure the watchdog as soon as possible in the boot +// process, because watchdog initialization at hardware reset on SAM3X8E +// is unreliable, and there is risk of unintended resets if we delay +// that initialization to a later time. +void watchdogSetup() { + + #if ENABLED(USE_WATCHDOG) + + // 4 seconds timeout + 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 + // frequency is therefore 32768 / 128 = 256 Hz + timeout = (timeout << 8) / 1000; + if (timeout == 0) + timeout = 1; + else if (timeout > 0xFFF) + timeout = 0xFFF; + + // We want to enable the watchdog with the specified timeout + uint32_t value = + WDT_MR_WDV(timeout) | // With the specified timeout + WDT_MR_WDD(timeout) | // and no invalid write window + #if !(SAMV70 || SAMV71 || SAME70 || SAMS70) + WDT_MR_WDRPROC | // WDT fault resets processor only - We want + // to keep PIO controller state + #endif + WDT_MR_WDDBGHLT | // WDT stops in debug state. + WDT_MR_WDIDLEHLT; // WDT stops in idle state. + + #if ENABLED(WATCHDOG_RESET_MANUAL) + // We enable the watchdog timer, but only for the interrupt. + + // Configure WDT to only trigger an interrupt + value |= WDT_MR_WDFIEN; // Enable WDT fault interrupt. + + // Disable WDT interrupt (just in case, to avoid triggering it!) + NVIC_DisableIRQ(WDT_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(); + + // Initialize WDT with the given parameters + WDT_Enable(WDT, value); + + // Configure and enable WDT interrupt. + NVIC_ClearPendingIRQ(WDT_IRQn); + NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups + NVIC_EnableIRQ(WDT_IRQn); + + #else + + // a WDT fault triggers a reset + value |= WDT_MR_WDRSTEN; + + // Initialize WDT with the given parameters + WDT_Enable(WDT, value); + + #endif + + // Reset the watchdog + WDT_Restart(WDT); + + #else + + // Make sure to completely disable the Watchdog + WDT_Disable(WDT); + + #endif +} + +// ------------------------ +// Free Memory Accessor +// ------------------------ + extern "C" { extern unsigned int _ebss; // end of bss section } @@ -82,6 +180,10 @@ int freeMemory() { return (int)&free_memory - (heap_end ?: (int)&_ebss); } +// ------------------------ +// Serial Ports +// ------------------------ + // Forward the default serial ports #if USING_HW_SERIAL0 DefaultSerial1 MSerial0(false, Serial); diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index d00c4d3da102..4d3f4823a517 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -32,7 +32,6 @@ #include "../shared/math_32bit.h" #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include @@ -115,8 +114,8 @@ typedef Servo hal_servo_t; // // Interrupts // -#define sei() noInterrupts() -#define cli() interrupts() +#define sei() interrupts() +#define cli() noInterrupts() #define CRITICAL_SECTION_START() const bool _irqon = hal.isr_state(); hal.isr_off() #define CRITICAL_SECTION_END() if (_irqon) hal.isr_on() @@ -176,9 +175,13 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} - static void init(); // Called early in setup() - static void init_board(); // Called less early in setup() - static void reboot(); // Software reset + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + + static void init(); // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Restart the firmware // Interrupts static bool isr_state() { return !__get_PRIMASK(); } diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index c5e8f2433d7d..7e3fe0135645 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -31,8 +31,6 @@ /** * HAL for Arduino Due and compatible (SAM3X8E) - * - * For ARDUINO_ARCH_SAM */ #ifdef ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/HAL_MinSerial.cpp b/Marlin/src/HAL/DUE/MinSerial.cpp similarity index 98% rename from Marlin/src/HAL/DUE/HAL_MinSerial.cpp rename to Marlin/src/HAL/DUE/MinSerial.cpp index 93c4ed67d63c..e5b3dbfe6f36 100644 --- a/Marlin/src/HAL/DUE/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/DUE/MinSerial.cpp @@ -25,7 +25,7 @@ #if ENABLED(POSTMORTEM_DEBUGGING) -#include "../shared/HAL_MinSerial.h" +#include "../shared/MinSerial.h" #include diff --git a/Marlin/src/HAL/DUE/Servo.cpp b/Marlin/src/HAL/DUE/Servo.cpp index 5524aa9cef47..2dab88238dd6 100644 --- a/Marlin/src/HAL/DUE/Servo.cpp +++ b/Marlin/src/HAL/DUE/Servo.cpp @@ -47,12 +47,12 @@ #include "../shared/servo.h" #include "../shared/servo_private.h" -static volatile int8_t Channel[_Nbr_16timers]; // counter for the servo being pulsed for each timer (or -1 if refresh interval) +static Flags<_Nbr_16timers> DisablePending; // ISR should disable the timer at the next timer reset // ------------------------ /// Interrupt handler for the TC0 channel 1. // ------------------------ -void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel); +void Servo_Handler(const timer16_Sequence_t, Tc*, const uint8_t); #ifdef _useTimer1 void HANDLER_FOR_TIMER1() { Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); } @@ -70,88 +70,92 @@ void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel); void HANDLER_FOR_TIMER5() { Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5); } #endif -void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) { - // clear interrupt - tc->TC_CHANNEL[channel].TC_SR; - if (Channel[timer] < 0) - tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer - else if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive) - extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated - - Channel[timer]++; // increment to the next channel - if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) { - tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks; - if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated - extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high +void Servo_Handler(const timer16_Sequence_t timer, Tc *tc, const uint8_t channel) { + static int8_t Channel[_Nbr_16timers]; // Servo counters to pulse (or -1 for refresh interval) + int8_t cho = Channel[timer]; // Handle the prior Channel[timer] first + if (cho < 0) { // Channel -1 indicates the refresh interval completed... + tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // ...so reset the timer + if (DisablePending[timer]) { + // Disabling only after the full servo period expires prevents + // pulses being too close together if immediately re-enabled. + DisablePending.clear(timer); + TC_Stop(tc, channel); + tc->TC_CHANNEL[channel].TC_SR; // clear interrupt + return; + } + } + else if (SERVO_INDEX(timer, cho) < ServoCount) // prior channel handled? + extDigitalWrite(SERVO(timer, cho).Pin.nbr, LOW); // pulse the prior channel LOW + + Channel[timer] = ++cho; // go to the next channel (or 0) + if (cho < SERVOS_PER_TIMER && SERVO_INDEX(timer, cho) < ServoCount) { + tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer, cho).ticks; + if (SERVO(timer, cho).Pin.isActive) // activated? + extDigitalWrite(SERVO(timer, cho).Pin.nbr, HIGH); // yes: pulse HIGH } else { // finished all channels so wait for the refresh period to expire before starting over - tc->TC_CHANNEL[channel].TC_RA = - tc->TC_CHANNEL[channel].TC_CV < usToTicks(REFRESH_INTERVAL) - 4 - ? (unsigned int)usToTicks(REFRESH_INTERVAL) // allow a few ticks to ensure the next OCR1A not missed - : tc->TC_CHANNEL[channel].TC_CV + 4; // at least REFRESH_INTERVAL has elapsed - Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel + const unsigned int cval = tc->TC_CHANNEL[channel].TC_CV + 128 / (SERVO_TIMER_PRESCALER), // allow 128 cycles to ensure the next CV not missed + ival = (unsigned int)usToTicks(REFRESH_INTERVAL); // at least REFRESH_INTERVAL has elapsed + tc->TC_CHANNEL[channel].TC_RA = max(cval, ival); + + Channel[timer] = -1; // reset the timer CCR on the next call } + + tc->TC_CHANNEL[channel].TC_SR; // clear interrupt } static void _initISR(Tc *tc, uint32_t channel, uint32_t id, IRQn_Type irqn) { pmc_enable_periph_clk(id); TC_Configure(tc, channel, - TC_CMR_TCCLKS_TIMER_CLOCK3 | // MCK/32 - TC_CMR_WAVE | // Waveform mode - TC_CMR_WAVSEL_UP_RC ); // Counter running up and reset when equals to RC - - /* 84MHz, MCK/32, for 1.5ms: 3937 */ - TC_SetRA(tc, channel, 2625); // 1ms - - /* Configure and enable interrupt */ + TC_CMR_WAVE // Waveform mode + | TC_CMR_WAVSEL_UP_RC // Counter running up and reset when equal to RC + | (SERVO_TIMER_PRESCALER == 2 ? TC_CMR_TCCLKS_TIMER_CLOCK1 : 0) // MCK/2 + | (SERVO_TIMER_PRESCALER == 8 ? TC_CMR_TCCLKS_TIMER_CLOCK2 : 0) // MCK/8 + | (SERVO_TIMER_PRESCALER == 32 ? TC_CMR_TCCLKS_TIMER_CLOCK3 : 0) // MCK/32 + | (SERVO_TIMER_PRESCALER == 128 ? TC_CMR_TCCLKS_TIMER_CLOCK4 : 0) // MCK/128 + ); + + // Wait 1ms before the first ISR + TC_SetRA(tc, channel, (F_CPU) / (SERVO_TIMER_PRESCALER) / 1000UL); // 1ms + + // Configure and enable interrupt NVIC_EnableIRQ(irqn); - // TC_IER_CPAS: RA Compare - tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS; + tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS; // TC_IER_CPAS: RA Compare // Enables the timer clock and performs a software reset to start the counting TC_Start(tc, channel); } -void initISR(timer16_Sequence_t timer) { - #ifdef _useTimer1 - if (timer == _timer1) - _initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1); - #endif - #ifdef _useTimer2 - if (timer == _timer2) - _initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2); - #endif - #ifdef _useTimer3 - if (timer == _timer3) - _initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3); - #endif - #ifdef _useTimer4 - if (timer == _timer4) - _initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4); - #endif - #ifdef _useTimer5 - if (timer == _timer5) - _initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5); - #endif +void initISR(const timer16_Sequence_t timer_index) { + CRITICAL_SECTION_START(); + const bool disable_soon = DisablePending[timer_index]; + DisablePending.clear(timer_index); + CRITICAL_SECTION_END(); + + if (!disable_soon) switch (timer_index) { + default: break; + #ifdef _useTimer1 + case _timer1: return _initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1); + #endif + #ifdef _useTimer2 + case _timer2: return _initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2); + #endif + #ifdef _useTimer3 + case _timer3: return _initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3); + #endif + #ifdef _useTimer4 + case _timer4: return _initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4); + #endif + #ifdef _useTimer5 + case _timer5: return _initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5); + #endif + } } -void finISR(timer16_Sequence_t) { - #ifdef _useTimer1 - TC_Stop(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); - #endif - #ifdef _useTimer2 - TC_Stop(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2); - #endif - #ifdef _useTimer3 - TC_Stop(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3); - #endif - #ifdef _useTimer4 - TC_Stop(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4); - #endif - #ifdef _useTimer5 - TC_Stop(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5); - #endif +void finISR(const timer16_Sequence_t timer_index) { + // Timer is disabled from the ISR, to ensure proper final pulse length. + DisablePending.set(timer_index); } #endif // HAS_SERVOS diff --git a/Marlin/src/HAL/DUE/ServoTimers.h b/Marlin/src/HAL/DUE/ServoTimers.h index c32c93825399..95bd404c8061 100644 --- a/Marlin/src/HAL/DUE/ServoTimers.h +++ b/Marlin/src/HAL/DUE/ServoTimers.h @@ -37,7 +37,7 @@ #define _useTimer5 #define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays -#define SERVO_TIMER_PRESCALER 32 // timer prescaler +#define SERVO_TIMER_PRESCALER 2 // timer prescaler /* TC0, chan 0 => TC0_Handler diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index 7ce4a84df531..607764155b0a 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -199,8 +199,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { for (i = 0; i > 2; i++) pageContents[i] = (((uint32_t*)data)[i]) | (~(pageContents[i] ^ ((uint32_t*)data)[i])); - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM PageWrite ", page); + DEBUG_ECHO_MSG("EEPROM PageWrite ", page); DEBUG_ECHOLNPGM(" in FLASH address ", (uint32_t)addrflash); DEBUG_ECHOLNPGM(" base address ", (uint32_t)getFlashStorage(0)); DEBUG_FLUSH(); @@ -245,8 +244,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { // Reenable interrupts __enable_irq(); - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Unlock failure for page ", page); + DEBUG_ECHO_MSG("EEPROM Unlock failure for page ", page); return false; } @@ -270,8 +268,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { // Reenable interrupts __enable_irq(); - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Write failure for page ", page); + DEBUG_ECHO_MSG("EEPROM Write failure for page ", page); return false; } @@ -286,8 +283,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { if (memcmp(getFlashStorage(page),data,PageSize)) { #ifdef EE_EMU_DEBUG - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Verify Write failure for page ", page); + DEBUG_ECHO_MSG("EEPROM Verify Write failure for page ", page); ee_Dump( page, (uint32_t *)addrflash); ee_Dump(-page, data); @@ -325,8 +321,7 @@ static bool ee_PageErase(uint16_t page) { uint16_t i; uint32_t addrflash = uint32_t(getFlashStorage(page)); - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM PageErase ", page); + DEBUG_ECHO_MSG("EEPROM PageErase ", page); DEBUG_ECHOLNPGM(" in FLASH address ", (uint32_t)addrflash); DEBUG_ECHOLNPGM(" base address ", (uint32_t)getFlashStorage(0)); DEBUG_FLUSH(); @@ -370,8 +365,7 @@ static bool ee_PageErase(uint16_t page) { // Reenable interrupts __enable_irq(); - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Unlock failure for page ",page); + DEBUG_ECHO_MSG("EEPROM Unlock failure for page ",page); return false; } @@ -394,8 +388,7 @@ static bool ee_PageErase(uint16_t page) { // Reenable interrupts __enable_irq(); - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Erase failure for page ",page); + DEBUG_ECHO_MSG("EEPROM Erase failure for page ",page); return false; } @@ -410,8 +403,7 @@ static bool ee_PageErase(uint16_t page) { uint32_t * aligned_src = (uint32_t *) addrflash; for (i = 0; i < PageSize >> 2; i++) { if (*aligned_src++ != 0xFFFFFFFF) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Verify Erase failure for page ",page); + DEBUG_ECHO_MSG("EEPROM Verify Erase failure for page ",page); ee_Dump(page, (uint32_t *)addrflash); return false; } @@ -921,8 +913,7 @@ static void ee_Init() { // If all groups seem to be used, default to first group if (curGroup >= GroupCount) curGroup = 0; - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Current Group: ",curGroup); + DEBUG_ECHO_MSG("EEPROM Current Group: ",curGroup); DEBUG_FLUSH(); // Now, validate that all the other group pages are empty @@ -931,8 +922,7 @@ static void ee_Init() { for (int page = 0; page < PagesPerGroup; page++) { if (!ee_IsPageClean(grp * PagesPerGroup + page)) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Page ", page, " not clean on group ", grp); + DEBUG_ECHO_MSG("EEPROM Page ", page, " not clean on group ", grp); DEBUG_FLUSH(); ee_PageErase(grp * PagesPerGroup + page); } @@ -948,15 +938,13 @@ static void ee_Init() { } } - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Active page: ", curPage); + DEBUG_ECHO_MSG("EEPROM Active page: ", curPage); DEBUG_FLUSH(); // Make sure the pages following the first clean one are also clean for (int page = curPage + 1; page < PagesPerGroup; page++) { if (!ee_IsPageClean(curGroup * PagesPerGroup + page)) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("EEPROM Page ", page, " not clean on active group ", curGroup); + DEBUG_ECHO_MSG("EEPROM Page ", page, " not clean on active group ", curGroup); DEBUG_FLUSH(); ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page)); ee_PageErase(curGroup * PagesPerGroup + page); diff --git a/Marlin/src/HAL/DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h index 75480acaf2e2..13484f7029d1 100644 --- a/Marlin/src/HAL/DUE/inc/SanityCheck.h +++ b/Marlin/src/HAL/DUE/inc/SanityCheck.h @@ -25,6 +25,30 @@ * Test Arduino Due specific configuration values for errors at compile-time. */ +/** + * Check for common serial pin conflicts + */ +#define CHECK_SERIAL_PIN(N) ( \ + X_STOP_PIN == N || Y_STOP_PIN == N || Z_STOP_PIN == N \ + || X_MIN_PIN == N || Y_MIN_PIN == N || Z_MIN_PIN == N \ + || X_MAX_PIN == N || Y_MAX_PIN == N || Z_MAX_PIN == N \ + || X_STEP_PIN == N || Y_STEP_PIN == N || Z_STEP_PIN == N \ + || X_DIR_PIN == N || Y_DIR_PIN == N || Z_DIR_PIN == N \ + || X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \ +) +#if CONF_SERIAL_IS(0) // D0-D1. No known conflicts. +#endif +#if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19)) + #error "Serial Port 1 pin D18 and/or D19 conflicts with another pin on the board." +#endif +#if CONF_SERIAL_IS(2) && (CHECK_SERIAL_PIN(16) || CHECK_SERIAL_PIN(17)) + #error "Serial Port 2 pin D16 and/or D17 conflicts with another pin on the board." +#endif +#if CONF_SERIAL_IS(3) && (CHECK_SERIAL_PIN(14) || CHECK_SERIAL_PIN(15)) + #error "Serial Port 3 pin D14 and/or D15 conflicts with another pin on the board." +#endif +#undef CHECK_SERIAL_PIN + /** * HARDWARE VS. SOFTWARE SPI COMPATIBILITY * diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp index a7bf7fbd6d85..e5647817b6f0 100644 --- a/Marlin/src/HAL/DUE/timers.cpp +++ b/Marlin/src/HAL/DUE/timers.cpp @@ -89,10 +89,17 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { NVIC_SetPriority(irq, timer_config[timer_num].priority); // wave mode, reset counter on match with RC, - TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1); + TC_Configure(tc, channel, + TC_CMR_WAVE + | TC_CMR_WAVSEL_UP_RC + | (HAL_TIMER_PRESCALER == 2 ? TC_CMR_TCCLKS_TIMER_CLOCK1 : 0) + | (HAL_TIMER_PRESCALER == 8 ? TC_CMR_TCCLKS_TIMER_CLOCK2 : 0) + | (HAL_TIMER_PRESCALER == 32 ? TC_CMR_TCCLKS_TIMER_CLOCK3 : 0) + | (HAL_TIMER_PRESCALER == 128 ? TC_CMR_TCCLKS_TIMER_CLOCK4 : 0) + ); // Set compare value - TC_SetRC(tc, channel, VARIANT_MCK / 2 / frequency); + TC_SetRC(tc, channel, VARIANT_MCK / (HAL_TIMER_PRESCALER) / frequency); // And start timer TC_Start(tc, channel); diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index bcfd07e268c5..dc35c77e6384 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -35,7 +35,8 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF -#define HAL_TIMER_RATE ((F_CPU) / 2) // frequency of timers peripherals +#define HAL_TIMER_PRESCALER 2 +#define HAL_TIMER_RATE ((F_CPU) / (HAL_TIMER_PRESCALER)) // frequency of timers peripherals #ifndef MF_TIMER_STEP #define MF_TIMER_STEP 2 // Timer Index for Stepper diff --git a/Marlin/src/HAL/DUE/usb/compiler.h b/Marlin/src/HAL/DUE/usb/compiler.h index f89e554c4562..633197914eef 100644 --- a/Marlin/src/HAL/DUE/usb/compiler.h +++ b/Marlin/src/HAL/DUE/usb/compiler.h @@ -1059,7 +1059,7 @@ static inline void convert_64_bit_to_byte_array(uint64_t value, uint8_t *data) while (val_index < 8) { data[val_index++] = value & 0xFF; - value = value >> 8; + value >>= 8; } } diff --git a/Marlin/src/HAL/DUE/watchdog.cpp b/Marlin/src/HAL/DUE/watchdog.cpp deleted file mode 100644 index e144db8291e3..000000000000 --- a/Marlin/src/HAL/DUE/watchdog.cpp +++ /dev/null @@ -1,114 +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 "../../inc/MarlinConfig.h" -#include "../../MarlinCore.h" -#include "watchdog.h" - -// Override Arduino runtime to either config or disable the watchdog -// -// We need to configure the watchdog as soon as possible in the boot -// process, because watchdog initialization at hardware reset on SAM3X8E -// is unreliable, and there is risk of unintended resets if we delay -// that initialization to a later time. -void watchdogSetup() { - - #if ENABLED(USE_WATCHDOG) - - // 4 seconds timeout - 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 - // frequency is therefore 32768 / 128 = 256 Hz - timeout = (timeout << 8) / 1000; - if (timeout == 0) - timeout = 1; - else if (timeout > 0xFFF) - timeout = 0xFFF; - - // We want to enable the watchdog with the specified timeout - uint32_t value = - WDT_MR_WDV(timeout) | // With the specified timeout - WDT_MR_WDD(timeout) | // and no invalid write window - #if !(SAMV70 || SAMV71 || SAME70 || SAMS70) - WDT_MR_WDRPROC | // WDT fault resets processor only - We want - // to keep PIO controller state - #endif - WDT_MR_WDDBGHLT | // WDT stops in debug state. - WDT_MR_WDIDLEHLT; // WDT stops in idle state. - - #if ENABLED(WATCHDOG_RESET_MANUAL) - // We enable the watchdog timer, but only for the interrupt. - - // Configure WDT to only trigger an interrupt - value |= WDT_MR_WDFIEN; // Enable WDT fault interrupt. - - // Disable WDT interrupt (just in case, to avoid triggering it!) - NVIC_DisableIRQ(WDT_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(); - - // Initialize WDT with the given parameters - WDT_Enable(WDT, value); - - // Configure and enable WDT interrupt. - NVIC_ClearPendingIRQ(WDT_IRQn); - NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups - NVIC_EnableIRQ(WDT_IRQn); - - #else - - // a WDT fault triggers a reset - value |= WDT_MR_WDRSTEN; - - // Initialize WDT with the given parameters - WDT_Enable(WDT, value); - - #endif - - // Reset the watchdog - WDT_Restart(WDT); - - #else - - // Make sure to completely disable the Watchdog - WDT_Disable(WDT); - - #endif -} - -#if ENABLED(USE_WATCHDOG) - // Initialize watchdog - On SAM3X, Watchdog was already configured - // and enabled or disabled at startup, so no need to reconfigure it - // here. - void watchdog_init() { - // Reset watchdog to start clean - WDT_Restart(WDT); - } -#endif // USE_WATCHDOG - -#endif diff --git a/Marlin/src/HAL/DUE/watchdog.h b/Marlin/src/HAL/DUE/watchdog.h deleted file mode 100644 index 5725a10007a7..000000000000 --- a/Marlin/src/HAL/DUE/watchdog.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 - -// Arduino Due core now has watchdog support - -#include "HAL.h" - -// Initialize watchdog with a 4 second interrupt time -void watchdog_init(); - -// Reset watchdog. MUST be called at least every 4 seconds after the -// first watchdog_init or AVR will go into emergency procedures. -inline void HAL_watchdog_refresh() { watchdogReset(); } diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 767f65d341bc..29f3be3c028a 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -65,6 +65,7 @@ portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED; // ------------------------ uint16_t MarlinHAL::adc_result; +pwm_pin_t MarlinHAL::pwm_pin_data[MAX_EXPANDER_BITS]; // ------------------------ // Private Variables @@ -179,6 +180,31 @@ void _delay_ms(int delay_ms) { delay(delay_ms); } // return free memory between end of heap (or end bss) and whatever is current int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + + extern "C" { + esp_err_t esp_task_wdt_reset(); + } + + void watchdogSetup() { + // do whatever. don't remove this function. + } + + void MarlinHAL::watchdog_init() { + // TODO + } + + // Reset watchdog. + void MarlinHAL::watchdog_refresh() { esp_task_wdt_reset(); } + +#endif + // ------------------------ // ADC // ------------------------ @@ -305,21 +331,46 @@ int8_t get_pwm_channel(const pin_t pin, const uint32_t freq, const uint16_t res) } void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=_BV(PWM_RESOLUTION)-1*/, const bool invert/*=false*/) { - const int8_t cid = get_pwm_channel(pin, PWM_FREQUENCY, PWM_RESOLUTION); - if (cid >= 0) { - uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, _BV(PWM_RESOLUTION)-1); - ledcWrite(cid, duty); - } + #if ENABLED(I2S_STEPPER_STREAM) + if (pin > 127) { + const uint8_t pinlo = pin & 0x7F; + pwm_pin_t &pindata = pwm_pin_data[pinlo]; + const uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, pindata.pwm_cycle_ticks); + if (duty == 0 || duty == pindata.pwm_cycle_ticks) { // max or min (i.e., on/off) + pindata.pwm_duty_ticks = 0; // turn off PWM for this pin + duty ? SBI32(i2s_port_data, pinlo) : CBI32(i2s_port_data, pinlo); // set pin level + } + else + pindata.pwm_duty_ticks = duty; // PWM duty count = # of 4µs ticks per full PWM cycle + } + else + #endif + { + const int8_t cid = get_pwm_channel(pin, PWM_FREQUENCY, PWM_RESOLUTION); + if (cid >= 0) { + const uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, _BV(PWM_RESOLUTION)-1); + ledcWrite(cid, duty); + } + } } int8_t MarlinHAL::set_pwm_frequency(const pin_t pin, const uint32_t f_desired) { - const int8_t cid = channel_for_pin(pin); - if (cid >= 0) { - if (f_desired == ledcReadFreq(cid)) return cid; // no freq change - ledcDetachPin(chan_pin[cid]); - chan_pin[cid] = 0; // remove old freq channel - } - return get_pwm_channel(pin, f_desired, PWM_RESOLUTION); // try for new one + #if ENABLED(I2S_STEPPER_STREAM) + if (pin > 127) { + pwm_pin_data[pin & 0x7F].pwm_cycle_ticks = 1000000UL / f_desired / 4; // # of 4µs ticks per full PWM cycle + return 0; + } + else + #endif + { + const int8_t cid = channel_for_pin(pin); + if (cid >= 0) { + if (f_desired == ledcReadFreq(cid)) return cid; // no freq change + ledcDetachPin(chan_pin[cid]); + chan_pin[cid] = 0; // remove old freq channel + } + return get_pwm_channel(pin, f_desired, PWM_RESOLUTION); // try for new one + } } // use hardware PWM if avail, if not then ISR diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index ba3627b1fd31..ddfedf92eed9 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -32,7 +32,6 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include "i2s.h" #if ENABLED(WIFISUPPORT) @@ -61,14 +60,17 @@ #endif #endif -#define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock) -#define CRITICAL_SECTION_END() portEXIT_CRITICAL(&spinlock) +#define CRITICAL_SECTION_START() portENTER_CRITICAL(&hal.spinlock) +#define CRITICAL_SECTION_END() portEXIT_CRITICAL(&hal.spinlock) #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment #define PWM_FREQUENCY 1000u // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency() #define PWM_RESOLUTION 10u // Default PWM bit resolution #define CHANNEL_MAX_NUM 15u // max PWM channel # to allocate (7 to only use low speed, 15 to use low & high) #define MAX_PWM_IOPIN 33u // hardware pwm pins < 34 +#ifndef MAX_EXPANDER_BITS + #define MAX_EXPANDER_BITS 32 // I2S expander bit width (max 32) +#endif // ------------------------ // Types @@ -77,6 +79,12 @@ typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs. typedef int16_t pin_t; +typedef struct pwm_pin { + uint32_t pwm_cycle_ticks = 1000000UL / (PWM_FREQUENCY) / 4; // # ticks per pwm cycle + uint32_t pwm_tick_count = 0; // current tick count + uint32_t pwm_duty_ticks = 0; // # of ticks for current duty cycle +} pwm_pin_t; + class Servo; typedef Servo hal_servo_t; @@ -172,9 +180,13 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} - static void init() {} // Called early in setup() - static void init_board(); // Called less early in setup() - static void reboot(); // Restart the firmware + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + + static void init() {} // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Restart the firmware // Interrupts static portMUX_TYPE spinlock; @@ -194,6 +206,8 @@ class MarlinHAL { // Free SRAM static int freeMemory(); + static pwm_pin_t pwm_pin_data[MAX_EXPANDER_BITS]; + // // ADC Methods // diff --git a/Marlin/src/HAL/ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp index 3e77b658360b..cf337eeb4622 100644 --- a/Marlin/src/HAL/ESP32/i2s.cpp +++ b/Marlin/src/HAL/ESP32/i2s.cpp @@ -337,6 +337,26 @@ uint8_t i2s_state(uint8_t pin) { } void i2s_push_sample() { + // Every 4µs (when space in DMA buffer) toggle each expander PWM output using + // the current duty cycle/frequency so they sync with any steps (once + // through the DMA/FIFO buffers). PWM signal inversion handled by other functions + LOOP_L_N(p, MAX_EXPANDER_BITS) { + if (hal.pwm_pin_data[p].pwm_duty_ticks > 0) { // pin has active pwm? + if (hal.pwm_pin_data[p].pwm_tick_count == 0) { + if (TEST32(i2s_port_data, p)) { // hi->lo + CBI32(i2s_port_data, p); + hal.pwm_pin_data[p].pwm_tick_count = hal.pwm_pin_data[p].pwm_cycle_ticks - hal.pwm_pin_data[p].pwm_duty_ticks; + } + else { // lo->hi + SBI32(i2s_port_data, p); + hal.pwm_pin_data[p].pwm_tick_count = hal.pwm_pin_data[p].pwm_duty_ticks; + } + } + else + hal.pwm_pin_data[p].pwm_tick_count--; + } + } + dma.current[dma.rw_pos++] = i2s_port_data; } diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h b/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h index 5f1c4b16019d..3ca806897a89 100644 --- a/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h @@ -20,3 +20,10 @@ * */ #pragma once + +// +// Board-specific options need to be defined before HAL.h +// +#if MB(MKS_TINYBEE) + #define MAX_EXPANDER_BITS 24 // TinyBee has 3 x HC595 +#endif diff --git a/Marlin/src/HAL/ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h index 04d70ec14f0b..3ccb15989f33 100644 --- a/Marlin/src/HAL/ESP32/inc/SanityCheck.h +++ b/Marlin/src/HAL/ESP32/inc/SanityCheck.h @@ -48,3 +48,7 @@ #if USING_PULLDOWNS #error "PULLDOWN pin mode is not available on ESP32 boards." #endif + +#if BOTH(I2S_STEPPER_STREAM, LIN_ADVANCE) + #error "I2S stream is currently incompatible with LIN_ADVANCE." +#endif diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index 5437e8181b95..a445035b2b43 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -23,24 +23,17 @@ */ #ifdef ARDUINO_ARCH_ESP32 -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #if EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1) #include -#include "Arduino.h" #include "../shared/HAL_SPI.h" #include "HAL.h" #include "SPI.h" static SPISettings spiConfig; -#define MDOGLCD_MOSI 23 -#define MDOGLCD_SCK 18 -#define MLCD_RESET_PIN 0 -#define MLCD_PINS_DC 4 -#define MDOGLCD_CS 21 -#define MDOGLCD_A0 4 #ifndef LCD_SPI_SPEED #ifdef SD_SPI_SPEED @@ -61,24 +54,24 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt case U8G_COM_MSG_STOP: break; case U8G_COM_MSG_INIT: - OUT_WRITE(MDOGLCD_CS, HIGH); - OUT_WRITE(MDOGLCD_A0, HIGH); - OUT_WRITE(MLCD_RESET_PIN, HIGH); + OUT_WRITE(DOGLCD_CS, HIGH); + OUT_WRITE(DOGLCD_A0, HIGH); + OUT_WRITE(LCD_RESET_PIN, HIGH); u8g_Delay(5); spiBegin(); spiInit(LCD_SPI_SPEED); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ - WRITE(MDOGLCD_A0, arg_val ? HIGH : LOW); + WRITE(DOGLCD_A0, arg_val ? HIGH : LOW); break; case U8G_COM_MSG_CHIP_SELECT: /* arg_val == 0 means HIGH level of U8G_PI_CS */ - WRITE(MDOGLCD_CS, arg_val ? LOW : HIGH); + WRITE(DOGLCD_CS, arg_val ? LOW : HIGH); break; case U8G_COM_MSG_RESET: - WRITE(MLCD_RESET_PIN, arg_val); + WRITE(LCD_RESET_PIN, arg_val); break; case U8G_COM_MSG_WRITE_BYTE: diff --git a/Marlin/src/HAL/ESP32/watchdog.cpp b/Marlin/src/HAL/ESP32/watchdog.cpp deleted file mode 100644 index 5ec03c46079b..000000000000 --- a/Marlin/src/HAL/ESP32/watchdog.cpp +++ /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 . - * - */ -#ifdef ARDUINO_ARCH_ESP32 - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout - -#include "watchdog.h" - -void watchdogSetup() { - // do whatever. don't remove this function. -} - -void watchdog_init() { - // TODO -} - -#endif // USE_WATCHDOG - -#endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index 0cd836af2b68..518657801905 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -28,6 +28,7 @@ #endif #include HAL_PATH(.,HAL.h) +extern MarlinHAL hal; #define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION) @@ -44,7 +45,3 @@ #ifndef PGMSTR #define PGMSTR(NAM,STR) const char NAM[] = STR #endif - -inline void watchdog_refresh() { - TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); -} diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 43899c632de5..22c3e521f086 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -21,6 +21,8 @@ */ #pragma once +#include "../../inc/MarlinConfigPre.h" + #include #include #include @@ -29,12 +31,10 @@ #include #include "hardware/Clock.h" - #include "../shared/Marduino.h" #include "../shared/math_32bit.h" #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include "serial.h" // ------------------------ @@ -106,9 +106,13 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} + // Watchdog + static void watchdog_init() {} + static void watchdog_refresh() {} + static void init() {} // Called early in setup() static void init_board() {} // Called less early in setup() - static void reboot(); // Reset the application state and GPIO + static void reboot(); // Reset the application state and GPIO // Interrupts static bool isr_state() { return true; } diff --git a/Marlin/src/HAL/LINUX/eeprom.cpp b/Marlin/src/HAL/LINUX/eeprom.cpp index 532f323c6edb..f878bba6a51b 100644 --- a/Marlin/src/HAL/LINUX/eeprom.cpp +++ b/Marlin/src/HAL/LINUX/eeprom.cpp @@ -69,12 +69,12 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui std::size_t bytes_written = 0; for (std::size_t i = 0; i < size; i++) { - buffer[pos+i] = value[i]; - bytes_written ++; + buffer[pos + i] = value[i]; + bytes_written++; } crc16(crc, value, size); - pos = pos + size; + pos += size; return (bytes_written != size); // return true for any error } @@ -82,21 +82,21 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uin std::size_t bytes_read = 0; if (writing) { for (std::size_t i = 0; i < size; i++) { - value[i] = buffer[pos+i]; - bytes_read ++; + value[i] = buffer[pos + i]; + bytes_read++; } crc16(crc, value, size); } else { uint8_t temp[size]; for (std::size_t i = 0; i < size; i++) { - temp[i] = buffer[pos+i]; - bytes_read ++; + temp[i] = buffer[pos + i]; + bytes_read++; } crc16(crc, temp, size); } - pos = pos + size; + pos += size; return bytes_read != size; // return true for any error } diff --git a/Marlin/src/HAL/LINUX/hardware/Heater.h b/Marlin/src/HAL/LINUX/hardware/Heater.h index b17078d0b739..6d590ce6c55e 100644 --- a/Marlin/src/HAL/LINUX/hardware/Heater.h +++ b/Marlin/src/HAL/LINUX/hardware/Heater.h @@ -26,8 +26,8 @@ struct LowpassFilter { uint64_t data_delay = 0; uint16_t update(uint16_t value) { - data_delay = data_delay - (data_delay >> 6) + value; - return (uint16_t)(data_delay >> 6); + data_delay += value - (data_delay >> 6); + return uint16_t(data_delay >> 6); } }; diff --git a/Marlin/src/HAL/LINUX/watchdog.cpp b/Marlin/src/HAL/LINUX/watchdog.cpp deleted file mode 100644 index 84202e48b6c5..000000000000 --- a/Marlin/src/HAL/LINUX/watchdog.cpp +++ /dev/null @@ -1,37 +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 __PLAT_LINUX__ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#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() {} - -#endif - -#endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index 541848b08acc..9ff3a6ba598f 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -25,10 +25,6 @@ #include "../shared/Delay.h" #include "../../../gcode/parser.h" -#if ENABLED(USE_WATCHDOG) - #include "watchdog.h" -#endif - DefaultSerial1 USBSerial(false, UsbSerial); uint32_t MarlinHAL::adc_result = 0; @@ -61,9 +57,7 @@ uint8_t MarlinHAL::get_reset_source() { return RST_POWER_ON; } -void MarlinHAL::clear_reset_source() { - TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); -} +void MarlinHAL::clear_reset_source() { watchdog_clear_timeout_flag(); } void flashFirmware(const int16_t) { delay(500); // Give OS time to disconnect @@ -72,6 +66,52 @@ void flashFirmware(const int16_t) { hal.reboot(); } +#if ENABLED(USE_WATCHDOG) + + #include + + #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + + void MarlinHAL::watchdog_init() { + #if ENABLED(WATCHDOG_RESET_MANUAL) + // We enable the watchdog timer, but only for the interrupt. + + // Configure WDT to only trigger an interrupt + // Disable WDT interrupt (just in case, to avoid triggering it!) + NVIC_DisableIRQ(WDT_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(); + + // Configure WDT to only trigger an interrupt + // Initialize WDT with the given parameters + WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_INT_ONLY); + + // Configure and enable WDT interrupt. + NVIC_ClearPendingIRQ(WDT_IRQn); + NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups + NVIC_EnableIRQ(WDT_IRQn); + #else + WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET); + #endif + WDT_Start(WDT_TIMEOUT_US); + } + + void MarlinHAL::watchdog_refresh() { + WDT_Feed(); + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + TOGGLE(LED_PIN); // heartbeat indicator + #endif + } + + // Timeout state + bool MarlinHAL::watchdog_timed_out() { return TEST(WDT_ReadTimeOutFlag(), 0); } + void MarlinHAL::watchdog_clear_timeout_flag() { WDT_ClrTimeOutFlag(); } + +#endif // USE_WATCHDOG + // For M42/M43, scan command line for pin code // return index into pin map array if found and the pin is valid. // return dval if not found or not a valid pin. diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 0f26509129d5..b0eeb983b445 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -38,7 +38,6 @@ extern "C" volatile uint32_t _millis; #include "../shared/math_32bit.h" #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include "MarlinSerial.h" #include @@ -177,7 +176,7 @@ void flashFirmware(const int16_t); #define CPU_ST7920_DELAY_3 750 // ------------------------ -// Class Utilities +// Free Memory Accessor // ------------------------ #pragma GCC diagnostic push @@ -199,9 +198,9 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} - static void init(); // Called early in setup() + static void init(); // Called early in setup() static void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 + static void reboot(); // Restart the firmware from 0x0 // Interrupts static bool isr_state() { return !__get_PRIMASK(); } @@ -210,6 +209,12 @@ class MarlinHAL { static void delay_ms(const int ms) { _delay_ms(ms); } + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static bool watchdog_timed_out() IF_DISABLED(USE_WATCHDOG, { return false; }); + static void watchdog_clear_timeout_flag() IF_DISABLED(USE_WATCHDOG, {}); + // Tasks, called from idle() static void idletask(); diff --git a/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp b/Marlin/src/HAL/LPC1768/MinSerial.cpp similarity index 97% rename from Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp rename to Marlin/src/HAL/LPC1768/MinSerial.cpp index 57065c49ac83..7a1c038c0b0b 100644 --- a/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MinSerial.cpp @@ -26,7 +26,7 @@ #if ENABLED(POSTMORTEM_DEBUGGING) -#include "../shared/HAL_MinSerial.h" +#include "../shared/MinSerial.h" #include static void TX(char c) { _DBC(c); } diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp index f9286a74ac88..1bbc39d4a242 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp @@ -34,7 +34,7 @@ #include "../shared/eeprom_api.h" #ifndef MARLIN_EEPROM_SIZE - #define MARLIN_EEPROM_SIZE 0x8000 // 32KB‬ + #define MARLIN_EEPROM_SIZE 0x8000 // 32K #endif size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } diff --git a/Marlin/src/HAL/LPC1768/watchdog.cpp b/Marlin/src/HAL/LPC1768/watchdog.cpp deleted file mode 100644 index f23ccf5b512d..000000000000 --- a/Marlin/src/HAL/LPC1768/watchdog.cpp +++ /dev/null @@ -1,72 +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 "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#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. - - // Configure WDT to only trigger an interrupt - // Disable WDT interrupt (just in case, to avoid triggering it!) - NVIC_DisableIRQ(WDT_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(); - - // Configure WDT to only trigger an interrupt - // Initialize WDT with the given parameters - WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_INT_ONLY); - - // Configure and enable WDT interrupt. - NVIC_ClearPendingIRQ(WDT_IRQn); - NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups - NVIC_EnableIRQ(WDT_IRQn); - #else - WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET); - #endif - WDT_Start(WDT_TIMEOUT_US); -} - -void HAL_watchdog_refresh() { - WDT_Feed(); - #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) - TOGGLE(LED_PIN); // heartbeat indicator - #endif -} - -// Timeout state -bool watchdog_timed_out() { return TEST(WDT_ReadTimeOutFlag(), 0); } -void watchdog_clear_timeout_flag() { WDT_ClrTimeOutFlag(); } - -#endif // USE_WATCHDOG -#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/watchdog.h b/Marlin/src/HAL/LPC1768/watchdog.h deleted file mode 100644 index c843f0ed5571..000000000000 --- a/Marlin/src/HAL/LPC1768/watchdog.h +++ /dev/null @@ -1,28 +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 watchdog_init(); -void HAL_watchdog_refresh(); - -bool watchdog_timed_out(); -void watchdog_clear_timeout_flag(); diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 49a5b6ea560b..66203611447f 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -45,7 +45,6 @@ uint8_t _getc(); #include "../shared/math_32bit.h" #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include "serial.h" // ------------------------ @@ -186,7 +185,7 @@ constexpr inline char* strstr_constexpr(char* str, const char* target) { } // ------------------------ -// Class Utilities +// Free Memory Accessor // ------------------------ #pragma GCC diagnostic push @@ -208,6 +207,10 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static void init() {} // Called early in setup() static void init_board() {} // Called less early in setup() static void reboot(); // Restart the firmware from 0x0 diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp index 3b5acc1656cd..91b7e0f67f76 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp @@ -38,13 +38,13 @@ #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? -} + +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 diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index 14b6a437dccc..bd1c98bfa1d9 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -203,6 +203,40 @@ enum ADCIndex { ADC_COUNT }; +#if ENABLED(USE_WATCHDOG) + + #define WDT_TIMEOUT_REG TERN(WATCHDOG_DURATION_8S, WDT_CONFIG_PER_CYC8192, WDT_CONFIG_PER_CYC4096) // 4 or 8 second timeout + + void MarlinHAL::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. + + // 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->CTRLA.bit.ENABLE = false; // Disable watchdog for config + SYNC(WDT->SYNCBUSY.bit.ENABLE); + + 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 + + hal.watchdog_refresh(); + + WDT->CTRLA.reg = WDT_CTRLA_ENABLE; // Start watchdog now in normal mode + SYNC(WDT->SYNCBUSY.bit.ENABLE); + } + + // Reset watchdog. MUST be called at least every 4 seconds after the + // first watchdog_init or SAMD will go into emergency procedures. + void MarlinHAL::watchdog_refresh() { + SYNC(WDT->SYNCBUSY.bit.CLEAR); // Test first if previous is 'ongoing' to save time waiting for command execution + WDT->CLEAR.reg = WDT_CLEAR_CLEAR_KEY; + } + +#endif + // ------------------------ // Types // ------------------------ @@ -564,7 +598,7 @@ void MarlinHAL::dma_init() { void MarlinHAL::init() { TERN_(DMA_IS_REQUIRED, dma_init()); #if ENABLED(SDSUPPORT) - #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT) + #if HAS_SD_DETECT && SD_CONNECTION_IS(ONBOARD) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index abcc28098776..79ba8021f4fd 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -26,7 +26,6 @@ #include "../shared/math_32bit.h" #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #ifdef ADAFRUIT_GRAND_CENTRAL_M4 #include "MarlinSerial_AGCM4.h" @@ -157,6 +156,10 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static void init(); // Called early in setup() static void init_board() {} // Called less early in setup() static void reboot(); // Restart the firmware from 0x0 diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp index 23ab21c615c4..665322fe24bc 100644 --- a/Marlin/src/HAL/SAMD51/Servo.cpp +++ b/Marlin/src/HAL/SAMD51/Servo.cpp @@ -77,7 +77,8 @@ HAL_SERVO_TIMER_ISR() { ; const uint8_t tcChannel = TIMER_TCCHANNEL(timer); - if (currentServoIndex[timer] < 0) { + int8_t cho = currentServoIndex[timer]; // Handle the prior servo first + if (cho < 0) { // Servo -1 indicates the refresh interval completed... #if defined(_useTimer1) && defined(_useTimer2) if (currentServoIndex[timer ^ 1] >= 0) { // Wait for both channels @@ -86,45 +87,37 @@ HAL_SERVO_TIMER_ISR() { return; } #endif - tc->COUNT16.COUNT.reg = TC_COUNTER_START_VAL; + tc->COUNT16.COUNT.reg = TC_COUNTER_START_VAL; // ...so reset the timer SYNC(tc->COUNT16.SYNCBUSY.bit.COUNT); } - else if (SERVO_INDEX(timer, currentServoIndex[timer]) < ServoCount && SERVO(timer, currentServoIndex[timer]).Pin.isActive) - digitalWrite(SERVO(timer, currentServoIndex[timer]).Pin.nbr, LOW); // pulse this channel low if activated - - // Select the next servo controlled by this timer - currentServoIndex[timer]++; + else if (SERVO_INDEX(timer, cho) < ServoCount) // prior channel handled? + digitalWrite(SERVO(timer, cho).Pin.nbr, LOW); // pulse the prior channel LOW - if (SERVO_INDEX(timer, currentServoIndex[timer]) < ServoCount && currentServoIndex[timer] < SERVOS_PER_TIMER) { - if (SERVO(timer, currentServoIndex[timer]).Pin.isActive) // check if activated - digitalWrite(SERVO(timer, currentServoIndex[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high + currentServoIndex[timer] = ++cho; // go to the next channel (or 0) + if (cho < SERVOS_PER_TIMER && SERVO_INDEX(timer, cho) < ServoCount) { + if (SERVO(timer, cho).Pin.isActive) // activated? + digitalWrite(SERVO(timer, cho).Pin.nbr, HIGH); // yes: pulse HIGH - tc->COUNT16.CC[tcChannel].reg = getTimerCount() - (uint16_t)SERVO(timer, currentServoIndex[timer]).ticks; + tc->COUNT16.CC[tcChannel].reg = getTimerCount() - (uint16_t)SERVO(timer, cho).ticks; } else { // finished all channels so wait for the refresh period to expire before starting over - currentServoIndex[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel - - const uint16_t tcCounterValue = getTimerCount(); - - if ((TC_COUNTER_START_VAL - tcCounterValue) + 4UL < usToTicks(REFRESH_INTERVAL)) // allow a few ticks to ensure the next OCR1A not missed - tc->COUNT16.CC[tcChannel].reg = TC_COUNTER_START_VAL - (uint16_t)usToTicks(REFRESH_INTERVAL); - else - tc->COUNT16.CC[tcChannel].reg = (uint16_t)(tcCounterValue - 4UL); // at least REFRESH_INTERVAL has elapsed + currentServoIndex[timer] = -1; // reset the timer COUNT.reg on the next call + const uint16_t cval = getTimerCount() - 256 / (SERVO_TIMER_PRESCALER), // allow 256 cycles to ensure the next CV not missed + ival = (TC_COUNTER_START_VAL) - (uint16_t)usToTicks(REFRESH_INTERVAL); // at least REFRESH_INTERVAL has elapsed + tc->COUNT16.CC[tcChannel].reg = min(cval, ival); } if (tcChannel == 0) { SYNC(tc->COUNT16.SYNCBUSY.bit.CC0); - // Clear the interrupt - tc->COUNT16.INTFLAG.reg = TC_INTFLAG_MC0; + tc->COUNT16.INTFLAG.reg = TC_INTFLAG_MC0; // Clear the interrupt } else { SYNC(tc->COUNT16.SYNCBUSY.bit.CC1); - // Clear the interrupt - tc->COUNT16.INTFLAG.reg = TC_INTFLAG_MC1; + tc->COUNT16.INTFLAG.reg = TC_INTFLAG_MC1; // Clear the interrupt } } -void initISR(timer16_Sequence_t timer) { +void initISR(const timer16_Sequence_t timer) { Tc * const tc = timer_config[SERVO_TC].pTc; const uint8_t tcChannel = TIMER_TCCHANNEL(timer); @@ -201,9 +194,9 @@ void initISR(timer16_Sequence_t timer) { } } -void finISR(timer16_Sequence_t timer) { +void finISR(const timer16_Sequence_t timer_index) { Tc * const tc = timer_config[SERVO_TC].pTc; - const uint8_t tcChannel = TIMER_TCCHANNEL(timer); + const uint8_t tcChannel = TIMER_TCCHANNEL(timer_index); // Disable the match channel interrupt request tc->COUNT16.INTENCLR.reg = (tcChannel == 0) ? TC_INTENCLR_MC0 : TC_INTENCLR_MC1; diff --git a/Marlin/src/HAL/SAMD51/watchdog.cpp b/Marlin/src/HAL/SAMD51/watchdog.cpp deleted file mode 100644 index 9de451836aeb..000000000000 --- a/Marlin/src/HAL/SAMD51/watchdog.cpp +++ /dev/null @@ -1,54 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#ifdef __SAMD51__ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#include "watchdog.h" - -#define WDT_TIMEOUT_REG TERN(WATCHDOG_DURATION_8S, WDT_CONFIG_PER_CYC8192, WDT_CONFIG_PER_CYC4096) // 4 or 8 second timeout - -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. - - // 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->CTRLA.bit.ENABLE = false; // Disable watchdog for config - SYNC(WDT->SYNCBUSY.bit.ENABLE); - - 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 - - HAL_watchdog_refresh(); - - WDT->CTRLA.reg = WDT_CTRLA_ENABLE; // Start watchdog now in normal mode - SYNC(WDT->SYNCBUSY.bit.ENABLE); -} - -#endif // USE_WATCHDOG - -#endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/watchdog.h b/Marlin/src/HAL/SAMD51/watchdog.h deleted file mode 100644 index 2cd4788229b0..000000000000 --- a/Marlin/src/HAL/SAMD51/watchdog.h +++ /dev/null @@ -1,31 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -// Initialize watchdog with a 4 second interrupt time -void watchdog_init(); - -// Reset watchdog. MUST be called at least every 4 seconds after the -// first watchdog_init or SAMD will go into emergency procedures. -inline void HAL_watchdog_refresh() { - SYNC(WDT->SYNCBUSY.bit.CLEAR); // Test first if previous is 'ongoing' to save time waiting for command execution - WDT->CLEAR.reg = WDT_CLEAR_CLEAR_KEY; -} diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index d28f506db9d3..aff52f597f4d 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -24,14 +24,13 @@ #ifdef HAL_STM32 -#include "HAL.h" -#include "usb_serial.h" - #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" +#include "usb_serial.h" + #ifdef USBCON - DefaultSerial1 MSerial0(false, SerialUSB); + DefaultSerial1 MSerialUSB(false, SerialUSB); #endif #if ENABLED(SRAM_EEPROM_EMULATION) @@ -141,6 +140,29 @@ uint8_t MarlinHAL::get_reset_source() { void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + + #include + + void MarlinHAL::watchdog_init() { + IF_DISABLED(DISABLE_WATCHDOG_INIT, IWatchdog.begin(WDT_TIMEOUT_US)); + } + + void MarlinHAL::watchdog_refresh() { + IWatchdog.reload(); + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + TOGGLE(LED_PIN); // heartbeat indicator + #endif + } + +#endif + extern "C" { extern unsigned int _ebss; // end of bss section } diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index d88342b889b5..3e85aca293d2 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -30,7 +30,6 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" #include "Servo.h" -#include "watchdog.h" #include "MarlinSerial.h" #include "../../inc/MarlinConfigPre.h" @@ -51,57 +50,67 @@ #include #include "../../core/serial_hook.h" typedef ForwardSerial1Class< decltype(SerialUSB) > DefaultSerial1; - extern DefaultSerial1 MSerial0; + extern DefaultSerial1 MSerialUSB; #endif #define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) -#if SERIAL_PORT == -1 - #define MYSERIAL1 MSerial0 -#elif WITHIN(SERIAL_PORT, 1, 6) +#if WITHIN(SERIAL_PORT, 1, 6) #define MYSERIAL1 MSERIAL(SERIAL_PORT) +#elif !defined(USBCON) + #error "SERIAL_PORT must be from 1 to 6." +#elif SERIAL_PORT == -1 + #define MYSERIAL1 MSerialUSB #else - #error "SERIAL_PORT must be from 1 to 6. You can also use -1 if the board supports Native USB." + #error "SERIAL_PORT must be from 1 to 6, or -1 for Native USB." #endif #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == -1 - #define MYSERIAL2 MSerial0 - #elif WITHIN(SERIAL_PORT_2, 1, 6) + #if WITHIN(SERIAL_PORT_2, 1, 6) #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) + #elif !defined(USBCON) + #error "SERIAL_PORT must be from 1 to 6." + #elif SERIAL_PORT_2 == -1 + #define MYSERIAL2 MSerialUSB #else - #error "SERIAL_PORT_2 must be from 1 to 6. You can also use -1 if the board supports Native USB." + #error "SERIAL_PORT_2 must be from 1 to 6, or -1 for Native USB." #endif #endif #ifdef SERIAL_PORT_3 - #if SERIAL_PORT_3 == -1 - #define MYSERIAL3 MSerial0 - #elif WITHIN(SERIAL_PORT_3, 1, 6) + #if WITHIN(SERIAL_PORT_3, 1, 6) #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #elif !defined(USBCON) + #error "SERIAL_PORT must be from 1 to 6." + #elif SERIAL_PORT_3 == -1 + #define MYSERIAL3 MSerialUSB #else - #error "SERIAL_PORT_3 must be from 1 to 6. You can also use -1 if the board supports Native USB." + #error "SERIAL_PORT_3 must be from 1 to 6, or -1 for Native USB." #endif #endif #ifdef MMU2_SERIAL_PORT - #if MMU2_SERIAL_PORT == -1 - #define MMU2_SERIAL MSerial0 - #elif WITHIN(MMU2_SERIAL_PORT, 1, 6) + #if WITHIN(MMU2_SERIAL_PORT, 1, 6) #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) + #elif !defined(USBCON) + #error "SERIAL_PORT must be from 1 to 6." + #elif MMU2_SERIAL_PORT == -1 + #define MMU2_SERIAL MSerialUSB #else - #error "MMU2_SERIAL_PORT must be from 1 to 6. You can also use -1 if the board supports Native USB." + #error "MMU2_SERIAL_PORT must be from 1 to 6, or -1 for Native USB." #endif #endif #ifdef LCD_SERIAL_PORT - #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL MSerial0 - #elif WITHIN(LCD_SERIAL_PORT, 1, 6) + #if WITHIN(LCD_SERIAL_PORT, 1, 6) #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) + #elif !defined(USBCON) + #error "SERIAL_PORT must be from 1 to 6." + #elif LCD_SERIAL_PORT == -1 + #define LCD_SERIAL MSerialUSB #else - #error "LCD_SERIAL_PORT must be from 1 to 6. You can also use -1 if the board supports Native USB." + #error "LCD_SERIAL_PORT must be from 1 to 6, or -1 for Native USB." #endif #if HAS_DGUS_LCD #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() @@ -208,9 +217,13 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} - static void init(); // Called early in setup() + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + + static void init(); // Called early in setup() static void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 + static void reboot(); // Restart the firmware from 0x0 // Interrupts static bool isr_state() { return !__get_PRIMASK(); } diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/MinSerial.cpp similarity index 97% rename from Marlin/src/HAL/STM32/HAL_MinSerial.cpp rename to Marlin/src/HAL/STM32/MinSerial.cpp index b6e86b72daa9..b0fcff20c172 100644 --- a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/STM32/MinSerial.cpp @@ -28,8 +28,7 @@ #if ENABLED(POSTMORTEM_DEBUGGING) -#include "../shared/HAL_MinSerial.h" -#include "watchdog.h" +#include "../shared/MinSerial.h" /* Instruction Synchronization Barrier */ #define isb() __asm__ __volatile__ ("isb" : : : "memory") @@ -120,7 +119,7 @@ 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()); + hal.watchdog_refresh(); sw_barrier(); } regs->DR = c; diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index 4f85af0d446a..a40bec9d644d 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -57,7 +57,7 @@ class Sd2CardUSBMscHandler : public USBMscHandler { auto sd2card = diskIODriver(); // single block if (blkLen == 1) { - watchdog_refresh(); + hal.watchdog_refresh(); sd2card->writeBlock(blkAddr, pBuf); return true; } @@ -65,7 +65,7 @@ class Sd2CardUSBMscHandler : public USBMscHandler { // multi block optimization sd2card->writeStart(blkAddr, blkLen); while (blkLen--) { - watchdog_refresh(); + hal.watchdog_refresh(); sd2card->writeData(pBuf); pBuf += BLOCK_SIZE; } @@ -77,7 +77,7 @@ class Sd2CardUSBMscHandler : public USBMscHandler { auto sd2card = diskIODriver(); // single block if (blkLen == 1) { - watchdog_refresh(); + hal.watchdog_refresh(); sd2card->readBlock(blkAddr, pBuf); return true; } @@ -85,7 +85,7 @@ class Sd2CardUSBMscHandler : public USBMscHandler { // multi block optimization sd2card->readStart(blkAddr); while (blkLen--) { - watchdog_refresh(); + hal.watchdog_refresh(); sd2card->readData(pBuf); pBuf += BLOCK_SIZE; } diff --git a/Marlin/src/HAL/STM32/sdio.cpp b/Marlin/src/HAL/STM32/sdio.cpp index 0af5f9040e54..e958d8c3bc48 100644 --- a/Marlin/src/HAL/STM32/sdio.cpp +++ b/Marlin/src/HAL/STM32/sdio.cpp @@ -35,42 +35,15 @@ // use local drivers #if defined(STM32F103xE) || defined(STM32F103xG) - #include - #include + #include #elif defined(STM32F4xx) - #include - #include - #include - #include + #include #elif defined(STM32F7xx) - #include - #include - #include - #include + #include +#elif defined(STM32H7xx) + #include #else - #error "SDIO only supported with STM32F103xE, STM32F103xG, STM32F4xx, or STM32F7xx." -#endif - -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 + #error "SDIO only supported with STM32F103xE, STM32F103xG, STM32F4xx, STM32F7xx, or STM32H7xx." #endif // Target Clock, configurable. Default is 18MHz, from STM32F1 @@ -78,223 +51,209 @@ DMA_HandleTypeDef hdma_sdio; #define SDIO_CLOCK 18000000 // 18 MHz #endif -// SDIO retries, configurable. Default is 3, from STM32F1 -#ifndef SDIO_READ_RETRIES - #define SDIO_READ_RETRIES 3 -#endif +#define SD_TIMEOUT 1000 // ms // 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; +#if defined(STM32F1xx) + DMA_HandleTypeDef hdma_sdio; + extern "C" void DMA2_Channel4_5_IRQHandler(void) { + HAL_DMA_IRQHandler(&hdma_sdio); + } +#elif defined(STM32F4xx) + DMA_HandleTypeDef hdma_sdio_rx; + DMA_HandleTypeDef hdma_sdio_tx; + extern "C" void DMA2_Stream3_IRQHandler(void) { + HAL_DMA_IRQHandler(&hdma_sdio_rx); + } - __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks - __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks + extern "C" void DMA2_Stream6_IRQHandler(void) { + HAL_DMA_IRQHandler(&hdma_sdio_tx); + } +#elif defined(STM32H7xx) + #define __HAL_RCC_SDIO_FORCE_RESET __HAL_RCC_SDMMC1_FORCE_RESET + #define __HAL_RCC_SDIO_RELEASE_RESET __HAL_RCC_SDMMC1_RELEASE_RESET + #define __HAL_RCC_SDIO_CLK_ENABLE __HAL_RCC_SDMMC1_CLK_ENABLE + #define SDIO SDMMC1 + #define SDIO_IRQn SDMMC1_IRQn + #define SDIO_IRQHandler SDMMC1_IRQHandler + #define SDIO_CLOCK_EDGE_RISING SDMMC_CLOCK_EDGE_RISING + #define SDIO_CLOCK_POWER_SAVE_DISABLE SDMMC_CLOCK_POWER_SAVE_DISABLE + #define SDIO_BUS_WIDE_1B SDMMC_BUS_WIDE_1B + #define SDIO_BUS_WIDE_4B SDMMC_BUS_WIDE_4B + #define SDIO_HARDWARE_FLOW_CONTROL_DISABLE SDMMC_HARDWARE_FLOW_CONTROL_DISABLE +#endif - GPIO_InitTypeDef GPIO_InitStruct; +uint8_t waitingRxCplt = 0; +uint8_t waitingTxCplt = 0; +SD_HandleTypeDef hsd; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = 1; //GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; +extern "C" void SDIO_IRQHandler(void) { + HAL_SD_IRQHandler(&hsd); +} - #if DISABLED(STM32F1xx) - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - #endif +void HAL_SD_TxCpltCallback(SD_HandleTypeDef *hsdio) { + waitingTxCplt = 0; +} - GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); +void HAL_SD_RxCpltCallback(SD_HandleTypeDef *hsdio) { + waitingRxCplt = 0; +} +void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { + pinmap_pinout(PC_12, PinMap_SD); + pinmap_pinout(PD_2, PinMap_SD); + pinmap_pinout(PC_8, PinMap_SD); #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); + // D1-D3 + pinmap_pinout(PC_9, PinMap_SD); + pinmap_pinout(PC_10, PinMap_SD); + pinmap_pinout(PC_11, PinMap_SD); #endif - // Configure PD.02 CMD line - GPIO_InitStruct.Pin = GPIO_PIN_2; - HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + __HAL_RCC_SDIO_CLK_ENABLE(); + HAL_NVIC_EnableIRQ(SDIO_IRQn); - // Setup DMA + // DMA Config #if defined(STM32F1xx) - hdma_sdio.Init.Mode = DMA_NORMAL; - hdma_sdio.Instance = DMA2_Channel4; + __HAL_RCC_DMA2_CLK_ENABLE(); HAL_NVIC_EnableIRQ(DMA2_Channel4_5_IRQn); + hdma_sdio.Instance = DMA2_Channel4; + hdma_sdio.Init.Direction = DMA_PERIPH_TO_MEMORY; + 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.Mode = DMA_NORMAL; + hdma_sdio.Init.Priority = DMA_PRIORITY_LOW; + HAL_DMA_Init(&hdma_sdio); + + __HAL_LINKDMA(hsd, hdmarx ,hdma_sdio); + __HAL_LINKDMA(hsd, hdmatx, hdma_sdio); #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_RCC_DMA2_CLK_ENABLE(); HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn); + HAL_NVIC_EnableIRQ(DMA2_Stream6_IRQn); + hdma_sdio_rx.Instance = DMA2_Stream3; + hdma_sdio_rx.Init.Channel = DMA_CHANNEL_4; + hdma_sdio_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_sdio_rx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_sdio_rx.Init.MemInc = DMA_MINC_ENABLE; + hdma_sdio_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_sdio_rx.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; + hdma_sdio_rx.Init.Mode = DMA_PFCTRL; + hdma_sdio_rx.Init.Priority = DMA_PRIORITY_LOW; + hdma_sdio_rx.Init.FIFOMode = DMA_FIFOMODE_ENABLE; + hdma_sdio_rx.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + hdma_sdio_rx.Init.MemBurst = DMA_MBURST_INC4; + hdma_sdio_rx.Init.PeriphBurst = DMA_PBURST_INC4; + HAL_DMA_Init(&hdma_sdio_rx); + + __HAL_LINKDMA(hsd,hdmarx,hdma_sdio_rx); + + hdma_sdio_tx.Instance = DMA2_Stream6; + hdma_sdio_tx.Init.Channel = DMA_CHANNEL_4; + hdma_sdio_tx.Init.Direction = DMA_MEMORY_TO_PERIPH; + hdma_sdio_tx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_sdio_tx.Init.MemInc = DMA_MINC_ENABLE; + hdma_sdio_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_sdio_tx.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; + hdma_sdio_tx.Init.Mode = DMA_PFCTRL; + hdma_sdio_tx.Init.Priority = DMA_PRIORITY_LOW; + hdma_sdio_tx.Init.FIFOMode = DMA_FIFOMODE_ENABLE; + hdma_sdio_tx.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + hdma_sdio_tx.Init.MemBurst = DMA_MBURST_INC4; + hdma_sdio_tx.Init.PeriphBurst = DMA_PBURST_INC4; + HAL_DMA_Init(&hdma_sdio_tx); + + __HAL_LINKDMA(hsd,hdmatx,hdma_sdio_tx); #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 +void HAL_SD_MspDeInit(SD_HandleTypeDef *hsd) { + #if !defined(STM32F1xx) __HAL_RCC_SDIO_FORCE_RESET(); - delay(2); + delay(10); __HAL_RCC_SDIO_RELEASE_RESET(); - delay(2); - __HAL_RCC_SDIO_CLK_ENABLE(); - - __HAL_RCC_DMA2_FORCE_RESET(); - delay(2); - __HAL_RCC_DMA2_RELEASE_RESET(); - delay(2); - __HAL_RCC_DMA2_CLK_ENABLE(); + delay(10); #endif - - //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 +static uint32_t clock_to_divider(uint32_t clk) { + #if defined(STM32H7xx) + // SDMMC_CK frequency = sdmmc_ker_ck / [2 * CLKDIV]. + uint32_t sdmmc_clk = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_SDMMC); + return sdmmc_clk / (2U * SDIO_CLOCK) + (sdmmc_clk % (2U * SDIO_CLOCK) != 0); + #else + // 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; + #endif } bool SDIO_Init() { - uint8_t retryCnt = SDIO_READ_RETRIES; + HAL_StatusTypeDef sd_state = HAL_OK; + if (hsd.Instance == SDIO) + HAL_SD_DeInit(&hsd); - bool status; + /* HAL SD initialization */ 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 - } - - go_to_transfer_speed(); - - #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()); - 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 - } - go_to_transfer_speed(); + hsd.Init.ClockEdge = SDIO_CLOCK_EDGE_RISING; + 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 = clock_to_divider(SDIO_CLOCK); + sd_state = HAL_SD_Init(&hsd); + + #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) + if (sd_state == HAL_OK) { + sd_state = HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B); } #endif - return true; + return (sd_state == HAL_OK) ? true : false; } -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; - - TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); +bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { + uint32_t timeout = HAL_GetTick() + SD_TIMEOUT; - 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); + while (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) { + if (HAL_GetTick() >= timeout) return false; } - if (ret != HAL_OK) { - HAL_DMA_Abort_IT(&hdma_sdio); - HAL_DMA_DeInit(&hdma_sdio); + waitingRxCplt = 1; + if (HAL_SD_ReadBlocks_DMA(&hsd, (uint8_t *)dst, block, 1) != HAL_OK) return false; - } - 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; - } - } + timeout = HAL_GetTick() + SD_TIMEOUT; + while (waitingRxCplt) + if (HAL_GetTick() >= timeout) return false; - 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 */ } + return true; +} - HAL_DMA_Abort_IT(&hdma_sdio); - HAL_DMA_DeInit(&hdma_sdio); +bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { + uint32_t timeout = HAL_GetTick() + SD_TIMEOUT; - timeout = millis() + 500; - while (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) if (ELAPSED(millis(), timeout)) return false; + while (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) + if (HAL_GetTick() >= timeout) return false; - return true; -} + waitingTxCplt = 1; + if (HAL_SD_WriteBlocks_DMA(&hsd, (uint8_t *)src, block, 1) != HAL_OK) + return false; -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; -} + timeout = HAL_GetTick() + SD_TIMEOUT; + while (waitingTxCplt) + if (HAL_GetTick() >= timeout) return false; -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; + return true; } bool SDIO_IsReady() { @@ -305,16 +264,5 @@ uint32_t SDIO_GetCardSize() { return (uint32_t)(hsd.SdCard.BlockNbr) * (hsd.SdCard.BlockSize); } -#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 - -extern "C" void SDIO_IRQHandler(void) { HAL_SD_IRQHandler(&hsd); } -extern "C" void DMA_IRQ_HANDLER(void) { HAL_DMA_IRQHandler(&hdma_sdio); } - #endif // SDIO_SUPPORT #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp index 92e14edb2057..180abc68b054 100644 --- a/Marlin/src/HAL/STM32/tft/gt911.cpp +++ b/Marlin/src/HAL/STM32/tft/gt911.cpp @@ -159,24 +159,28 @@ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_l void GT911::Init() { OUT_WRITE(GT911_RST_PIN, LOW); OUT_WRITE(GT911_INT_PIN, LOW); - delay(20); + delay(11); + WRITE(GT911_INT_PIN, HIGH); + delayMicroseconds(110); WRITE(GT911_RST_PIN, HIGH); + delay(6); + WRITE(GT911_INT_PIN, LOW); + delay(55); 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 + uint8_t clear_reg = 0x00; + write_reg(0x814E, 2, &clear_reg, 1); // 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) { + if (reg.REG.status >= 0x80 && reg.REG.status <= 0x85) { + read_reg(0x8150, 2, reg.map + 2, 38); 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; diff --git a/Marlin/src/HAL/STM32/tft/gt911.h b/Marlin/src/HAL/STM32/tft/gt911.h index 752a554d98ed..6ecfe8b82ec7 100644 --- a/Marlin/src/HAL/STM32/tft/gt911.h +++ b/Marlin/src/HAL/STM32/tft/gt911.h @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfig.h" -#define GT911_SLAVE_ADDRESS 0xBA +#define GT911_SLAVE_ADDRESS 0x28 #if !PIN_EXISTS(GT911_RST) #error "GT911_RST_PIN is not defined." diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp deleted file mode 100644 index 1eccdec4985d..000000000000 --- a/Marlin/src/HAL/STM32/watchdog.cpp +++ /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 . - * - */ - -#include "../platforms.h" - -#ifdef HAL_STM32 - -#include "../../inc/MarlinConfigPre.h" - -#if ENABLED(USE_WATCHDOG) - -#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout - -#include "../../inc/MarlinConfig.h" - -#include "watchdog.h" -#include - -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 -} - -#endif // USE_WATCHDOG -#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index 636dc742fcf5..4d3140001e82 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -83,6 +83,7 @@ // ------------------------ #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE + USBSerial SerialUSB; DefaultSerial1 MSerial0(true, SerialUSB); @@ -112,6 +113,47 @@ #endif #endif +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + #include + + void watchdogSetup() { + // do whatever. don't remove this function. + } + + /** + * 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 + + /** + * @brief Initialize the independent hardware watchdog. + * + * @return No return + * + * @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 MarlinHAL::watchdog_init() { + #if DISABLED(DISABLE_WATCHDOG_INIT) + iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD); + #endif + } + + // Reset watchdog. MUST be called every 4 or 8 seconds after the + // first watchdog_init or the STM32F1 will reset. + void MarlinHAL::watchdog_refresh() { + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + TOGGLE(LED_PIN); // heartbeat indicator + #endif + iwdg_feed(); + } + +#endif // USE_WATCHDOG + // ------------------------ // ADC // ------------------------ @@ -211,6 +253,10 @@ void MarlinHAL::idletask() { void MarlinHAL::reboot() { nvic_sys_reset(); } +// ------------------------ +// Free Memory Accessor +// ------------------------ + extern "C" { extern unsigned int _ebss; // end of bss section } @@ -243,9 +289,9 @@ extern "C" { } */ -// +// ------------------------ // ADC -// +// ------------------------ enum ADCIndex : uint8_t { OPTITEM(HAS_TEMP_ADC_0, TEMP_0) diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index a42dd89b8d27..b14b5f7e7926 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -34,7 +34,6 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include #include @@ -247,6 +246,10 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static void init(); // Called early in setup() static void init_board() {} // Called less early in setup() static void reboot(); // Restart the firmware from 0x0 diff --git a/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32F1/MinSerial.cpp similarity index 97% rename from Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp rename to Marlin/src/HAL/STM32F1/MinSerial.cpp index 0fc3d014d484..6cf68d8d8f45 100644 --- a/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MinSerial.cpp @@ -26,8 +26,7 @@ #if ENABLED(POSTMORTEM_DEBUGGING) -#include "../shared/HAL_MinSerial.h" -#include "watchdog.h" +#include "../shared/MinSerial.h" #include #include @@ -82,7 +81,7 @@ 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()); + hal.watchdog_refresh(); sw_barrier(); } dev->regs->DR = c; diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index 8dc1ef7b6a5b..47ffb631cf8f 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -147,17 +147,17 @@ void libServo::move(const int32_t value) { uint16_t SR = timer_get_status(tdev); if (SR & TIMER_SR_CC1IF) { // channel 1 off #ifdef SERVO0_PWM_OD - OUT_WRITE_OD(SERVO0_PIN, 1); // off + OUT_WRITE_OD(SERVO0_PIN, HIGH); // off #else - OUT_WRITE(SERVO0_PIN, 0); + OUT_WRITE(SERVO0_PIN, LOW); #endif timer_reset_status_bit(tdev, TIMER_SR_CC1IF_BIT); } if (SR & TIMER_SR_CC2IF) { // channel 2 resume #ifdef SERVO0_PWM_OD - OUT_WRITE_OD(SERVO0_PIN, 0); // on + OUT_WRITE_OD(SERVO0_PIN, LOW); // on #else - OUT_WRITE(SERVO0_PIN, 1); + OUT_WRITE(SERVO0_PIN, HIGH); #endif timer_reset_status_bit(tdev, TIMER_SR_CC2IF_BIT); } @@ -167,9 +167,9 @@ void libServo::move(const int32_t value) { timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0); if (!tdev) return false; #ifdef SERVO0_PWM_OD - OUT_WRITE_OD(inPin, 1); + OUT_WRITE_OD(inPin, HIGH); #else - OUT_WRITE(inPin, 0); + OUT_WRITE(inPin, LOW); #endif timer_pause(tdev); @@ -200,9 +200,9 @@ void libServo::move(const int32_t value) { timer_disable_irq(tdev, 1); timer_disable_irq(tdev, 2); #ifdef SERVO0_PWM_OD - OUT_WRITE_OD(pin, 1); // off + OUT_WRITE_OD(pin, HIGH); // off #else - OUT_WRITE(pin, 0); + OUT_WRITE(pin, LOW); #endif } } diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp index 9bf6bbb32bc7..f447cec81107 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp @@ -30,7 +30,7 @@ SPIClass TFT_SPI::SPIx(1); void TFT_SPI::Init() { #if PIN_EXISTS(TFT_RESET) - OUT_WRITE(TFT_RST_PIN, HIGH); + OUT_WRITE(TFT_RESET_PIN, HIGH); delay(100); #endif diff --git a/Marlin/src/HAL/STM32F1/watchdog.cpp b/Marlin/src/HAL/STM32F1/watchdog.cpp deleted file mode 100644 index b812a4fa6403..000000000000 --- a/Marlin/src/HAL/STM32F1/watchdog.cpp +++ /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 . - * - */ - -/** - * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) - */ - -#ifdef __STM32F1__ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#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 - #endif - iwdg_feed(); -} - -void watchdogSetup() { - // do whatever. don't remove this function. -} - -/** - * @brief Initialized the independent hardware watchdog. - * - * @return No return - * - * @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) - iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD); - #endif -} - -#endif // USE_WATCHDOG -#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/watchdog.h b/Marlin/src/HAL/STM32F1/watchdog.h deleted file mode 100644 index 68920f8cb692..000000000000 --- a/Marlin/src/HAL/STM32F1/watchdog.h +++ /dev/null @@ -1,35 +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 - -/** - * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) - */ - -#include - -// Initialize watchdog with a 4 or 8 second countdown time -void watchdog_init(); - -// 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/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp index b923ab77b1f1..2892368967e4 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp @@ -44,25 +44,6 @@ #endif USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ - -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } -} - // ------------------------ // MarlinHAL Class // ------------------------ @@ -81,7 +62,31 @@ uint8_t MarlinHAL::get_reset_source() { return 0; } +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + #define WDT_TIMEOUT_MS TERN(WATCHDOG_DURATION_8S, 8000, 4000) // 4 or 8 second timeout + + void MarlinHAL::watchdog_init() { + WDOG_TOVALH = 0; + WDOG_TOVALL = WDT_TIMEOUT_MS; + WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN; + } + + void MarlinHAL::watchdog_refresh() { + // Watchdog refresh sequence + WDOG_REFRESH = 0xA602; + WDOG_REFRESH = 0xB480; + } + +#endif + +// ------------------------ // ADC +// ------------------------ void MarlinHAL::adc_init() { analog_init(); @@ -102,4 +107,23 @@ void MarlinHAL::adc_start(const pin_t pin) { uint16_t MarlinHAL::adc_value() { return ADC0_RA; } +// ------------------------ +// Free Memory Accessor +// ------------------------ + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } +} + #endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index dc0d2d3fa939..a7aa9f0da211 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -32,7 +32,6 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include @@ -135,6 +134,10 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static void init() {} // Called early in setup() static void init_board() {} // Called less early in setup() static void reboot(); // Restart the firmware from 0x0 diff --git a/Marlin/src/HAL/TEENSY31_32/watchdog.cpp b/Marlin/src/HAL/TEENSY31_32/watchdog.cpp deleted file mode 100644 index 5e21236129db..000000000000 --- a/Marlin/src/HAL/TEENSY31_32/watchdog.cpp +++ /dev/null @@ -1,40 +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 __MK20DX256__ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#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 = WDT_TIMEOUT_MS; - WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN; -} - -#endif // USE_WATCHDOG - -#endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/watchdog.h b/Marlin/src/HAL/TEENSY31_32/watchdog.h deleted file mode 100644 index b8b46a403013..000000000000 --- a/Marlin/src/HAL/TEENSY31_32/watchdog.h +++ /dev/null @@ -1,34 +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 "HAL.h" - -// Arduino Due core now has watchdog support - -void watchdog_init(); - -inline void HAL_watchdog_refresh() { - // Watchdog refresh sequence - WDOG_REFRESH = 0xA602; - WDOG_REFRESH = 0xB480; -} diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp index 54a5ad385536..bc02ac1c4524 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp @@ -43,33 +43,12 @@ USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ - -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } -} - // ------------------------ // MarlinHAL Class // ------------------------ void MarlinHAL::reboot() { _reboot_Teensyduino_(); } -// Reset - uint8_t MarlinHAL::get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; @@ -82,7 +61,31 @@ uint8_t MarlinHAL::get_reset_source() { return 0; } +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + #define WDT_TIMEOUT_MS TERN(WATCHDOG_DURATION_8S, 8000, 4000) // 4 or 8 second timeout + + void MarlinHAL::watchdog_init() { + WDOG_TOVALH = 0; + WDOG_TOVALL = WDT_TIMEOUT_MS; + WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN; + } + + void MarlinHAL::watchdog_refresh() { + // Watchdog refresh sequence + WDOG_REFRESH = 0xA602; + WDOG_REFRESH = 0xB480; + } + +#endif + +// ------------------------ // ADC +// ------------------------ int8_t MarlinHAL::adc_select; @@ -131,4 +134,23 @@ uint16_t MarlinHAL::adc_value() { return 0; } +// ------------------------ +// Free Memory Accessor +// ------------------------ + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } +} + #endif // __MK64FX512__ || __MK66FX1M0__ diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index c45f2aa49307..2a192e47189d 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -32,7 +32,6 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include #include @@ -118,7 +117,7 @@ typedef int8_t pin_t; #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) // ------------------------ -// Class Utilities +// Free Memory Accessor // ------------------------ #pragma GCC diagnostic push @@ -140,6 +139,10 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static void init() {} // Called early in setup() static void init_board() {} // Called less early in setup() static void reboot(); // Restart the firmware from 0x0 diff --git a/Marlin/src/HAL/TEENSY35_36/watchdog.cpp b/Marlin/src/HAL/TEENSY35_36/watchdog.cpp deleted file mode 100644 index 3825e2792869..000000000000 --- a/Marlin/src/HAL/TEENSY35_36/watchdog.cpp +++ /dev/null @@ -1,40 +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(__MK64FX512__) || defined(__MK66FX1M0__) - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#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 = WDT_TIMEOUT_MS; - WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN; -} - -#endif // USE_WATCHDOG - -#endif // __MK64FX512__ || __MK66FX1M0__ diff --git a/Marlin/src/HAL/TEENSY35_36/watchdog.h b/Marlin/src/HAL/TEENSY35_36/watchdog.h deleted file mode 100644 index 981b1f0bd20b..000000000000 --- a/Marlin/src/HAL/TEENSY35_36/watchdog.h +++ /dev/null @@ -1,30 +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 watchdog_init(); - -inline void HAL_watchdog_refresh() { - // Watchdog refresh sequence - WDOG_REFRESH = 0xA602; - WDOG_REFRESH = 0xB480; -} diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 68bd38f72ff8..1d02ab8575c3 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -44,25 +44,6 @@ #endif USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ - -#define __bss_end _ebss - -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - // Doesn't work on Teensy 4.x - uint32_t freeMemory() { - uint32_t free_memory; - free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end)); - return free_memory; - } -} - // ------------------------ // FastIO // ------------------------ @@ -97,7 +78,34 @@ void MarlinHAL::clear_reset_source() { SRC_SRSR = reset_source; } +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + #define WDT_TIMEOUT TERN(WATCHDOG_DURATION_8S, 8, 4) // 4 or 8 second timeout + + constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) / 0.5f; + + void MarlinHAL::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 MarlinHAL::watchdog_refresh() { + // Watchdog refresh sequence + WDOG1_WSR = 0x5555; + WDOG1_WSR = 0xAAAA; + } + +#endif + +// ------------------------ // ADC +// ------------------------ int8_t MarlinHAL::adc_select; @@ -180,4 +188,23 @@ uint16_t MarlinHAL::adc_value() { return 0; } +// ------------------------ +// Free Memory Accessor +// ------------------------ + +#define __bss_end _ebss + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + // Doesn't work on Teensy 4.x + uint32_t freeMemory() { + uint32_t free_memory; + free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end)); + return free_memory; + } +} + #endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index ea874da2faea..c54a2e8a0b64 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -32,7 +32,6 @@ #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "watchdog.h" #include #include @@ -140,7 +139,7 @@ typedef int8_t pin_t; bool is_output(pin_t pin); // ------------------------ -// Class Utilities +// Free Memory Accessor // ------------------------ #pragma GCC diagnostic push @@ -162,6 +161,10 @@ class MarlinHAL { // Earliest possible init, before setup() MarlinHAL() {} + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static void init() {} // Called early in setup() static void init_board() {} // Called less early in setup() static void reboot(); // Restart the firmware from 0x0 diff --git a/Marlin/src/HAL/TEENSY40_41/watchdog.cpp b/Marlin/src/HAL/TEENSY40_41/watchdog.cpp deleted file mode 100644 index dd7c0aa92f09..000000000000 --- a/Marlin/src/HAL/TEENSY40_41/watchdog.cpp +++ /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 . - * - */ -#ifdef __IMXRT1062__ - -/** - * HAL Watchdog for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A) - */ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(USE_WATCHDOG) - -#include "watchdog.h" - -#define WDT_TIMEOUT TERN(WATCHDOG_DURATION_8S, 8, 4) // 4 or 8 second timeout - -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() { - // Watchdog refresh sequence - WDOG1_WSR = 0x5555; - WDOG1_WSR = 0xAAAA; -} - -#endif // USE_WATCHDOG -#endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/shared/HAL_MinSerial.cpp b/Marlin/src/HAL/shared/MinSerial.cpp similarity index 97% rename from Marlin/src/HAL/shared/HAL_MinSerial.cpp rename to Marlin/src/HAL/shared/MinSerial.cpp index 9dda5fdf8c67..2e718d83dc12 100644 --- a/Marlin/src/HAL/shared/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/shared/MinSerial.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "HAL_MinSerial.h" +#include "MinSerial.h" #if ENABLED(POSTMORTEM_DEBUGGING) diff --git a/Marlin/src/HAL/shared/HAL_MinSerial.h b/Marlin/src/HAL/shared/MinSerial.h similarity index 100% rename from Marlin/src/HAL/shared/HAL_MinSerial.h rename to Marlin/src/HAL/shared/MinSerial.h diff --git a/Marlin/src/HAL/shared/backtrace/backtrace.cpp b/Marlin/src/HAL/shared/backtrace/backtrace.cpp index ad88de8385ac..33e8e65154a0 100644 --- a/Marlin/src/HAL/shared/backtrace/backtrace.cpp +++ b/Marlin/src/HAL/shared/backtrace/backtrace.cpp @@ -25,7 +25,7 @@ #include "unwinder.h" #include "unwmemaccess.h" -#include "../HAL_MinSerial.h" +#include "../MinSerial.h" #include // Dump a backtrace entry diff --git a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp index f1ee81ed4acb..148927a19f52 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp @@ -135,11 +135,11 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat while ((instruction = UnwTabGetNextInstruction(cb, ucb)) != -1) { if ((instruction & 0xC0) == 0x00) { // ARM_EXIDX_CMD_DATA_POP - /* vsp = vsp + (xxxxxx << 2) + 4 */ + /* vsp += (xxxxxx << 2) + 4 */ ucb->vrs[13] += ((instruction & 0x3F) << 2) + 4; } else if ((instruction & 0xC0) == 0x40) { // ARM_EXIDX_CMD_DATA_PUSH - /* vsp = vsp - (xxxxxx << 2) - 4 */ + /* vsp -= (xxxxxx << 2) - 4 */ ucb->vrs[13] -= ((instruction & 0x3F) << 2) - 4; } else if ((instruction & 0xF0) == 0x80) { diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index a106ed2b05e5..e54661c77071 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -54,7 +54,7 @@ #include "exception_hook.h" #include "../backtrace/backtrace.h" -#include "../HAL_MinSerial.h" +#include "../MinSerial.h" #define HW_REG(X) (*((volatile unsigned long *)(X))) @@ -221,7 +221,7 @@ bool resume_from_fault() { // 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(); + hal.watchdog_refresh(); while (millis() == last) { /* nada */ } last = millis(); MinSerial::TX('.'); diff --git a/Marlin/src/HAL/shared/servo.cpp b/Marlin/src/HAL/shared/servo.cpp index cfec6f301737..b838800de654 100644 --- a/Marlin/src/HAL/shared/servo.cpp +++ b/Marlin/src/HAL/shared/servo.cpp @@ -65,7 +65,7 @@ uint8_t ServoCount = 0; // the total number of attached /************ static functions common to all instances ***********************/ -static boolean isTimerActive(timer16_Sequence_t timer) { +static bool anyTimerChannelActive(const timer16_Sequence_t timer) { // returns true if any servo is active on this timer LOOP_L_N(channel, SERVOS_PER_TIMER) { if (SERVO(timer, channel).Pin.isActive) @@ -101,17 +101,18 @@ int8_t Servo::attach(const int inPin, const int inMin, const int inMax) { max = (MAX_PULSE_WIDTH - inMax) / 4; // initialize the timer if it has not already been initialized - timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); - if (!isTimerActive(timer)) initISR(timer); - servo_info[servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive + const timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); + if (!anyTimerChannelActive(timer)) initISR(timer); + servo_info[servoIndex].Pin.isActive = true; // this must be set after the check for anyTimerChannelActive return servoIndex; } void Servo::detach() { servo_info[servoIndex].Pin.isActive = false; - timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); - if (!isTimerActive(timer)) finISR(timer); + const timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); + if (!anyTimerChannelActive(timer)) finISR(timer); + //pinMode(servo_info[servoIndex].Pin.nbr, INPUT); // set servo pin to input } void Servo::write(int value) { diff --git a/Marlin/src/HAL/shared/servo_private.h b/Marlin/src/HAL/shared/servo_private.h index d85d8da8ba43..10cc5a198821 100644 --- a/Marlin/src/HAL/shared/servo_private.h +++ b/Marlin/src/HAL/shared/servo_private.h @@ -70,10 +70,10 @@ #define ticksToUs(_ticks) (unsigned(_ticks) * (SERVO_TIMER_PRESCALER) / clockCyclesPerMicrosecond()) // convenience macros -#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / (SERVOS_PER_TIMER))) // returns the timer controlling this servo -#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % (SERVOS_PER_TIMER)) // returns the index of the servo on this timer -#define SERVO_INDEX(_timer,_channel) ((_timer*(SERVOS_PER_TIMER)) + _channel) // macro to access servo index by timer and channel -#define SERVO(_timer,_channel) (servo_info[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel +#define SERVO_INDEX_TO_TIMER(_servo_nbr) timer16_Sequence_t(_servo_nbr / (SERVOS_PER_TIMER)) // the timer controlling this servo +#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % (SERVOS_PER_TIMER)) // the index of the servo on this timer +#define SERVO_INDEX(_timer,_channel) ((_timer*(SERVOS_PER_TIMER)) + _channel) // servo index by timer and channel +#define SERVO(_timer,_channel) servo_info[SERVO_INDEX(_timer,_channel)] // servo class by timer and channel // Types @@ -94,5 +94,5 @@ extern ServoInfo_t servo_info[MAX_SERVOS]; // Public functions -extern void initISR(timer16_Sequence_t timer); -extern void finISR(timer16_Sequence_t timer); +void initISR(const timer16_Sequence_t timer_index); +void finISR(const timer16_Sequence_t timer_index); diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 50172f98b95b..7a835da4979c 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -76,8 +76,6 @@ #include "lcd/e3v2/creality/dwin.h" #elif ENABLED(DWIN_LCD_PROUI) #include "lcd/e3v2/proui/dwin.h" - #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "lcd/e3v2/jyersui/dwin.h" #endif #endif @@ -97,7 +95,7 @@ #include "feature/host_actions.h" #endif -#if USE_BEEPER +#if HAS_BEEPER #include "libs/buzzer.h" #endif @@ -321,6 +319,10 @@ bool pin_is_protected(const pin_t pin) { #pragma GCC diagnostic pop +bool printer_busy() { + return planner.movesplanned() || printingIsActive(); +} + /** * A Print Job exists when the timer is running or SD is printing */ @@ -419,37 +421,38 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { kill(); } - // M18 / M84 : Handle steppers inactive time timeout - if (gcode.stepper_inactive_time) { - - static bool already_shutdown_steppers; // = false + const bool has_blocks = planner.has_blocks_queued(); // Any moves in the planner? + if (has_blocks) gcode.reset_stepper_timeout(ms); // Reset timeout for M18/M84, M85 max 'kill', and laser. - // Any moves in the planner? Resets both the M18/M84 - // activity timeout and the M85 max 'kill' timeout - if (planner.has_blocks_queued()) - gcode.reset_stepper_timeout(ms); - 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 - - // Individual axes will be disabled if configured - TERN_(DISABLE_INACTIVE_X, stepper.disable_axis(X_AXIS)); - TERN_(DISABLE_INACTIVE_Y, stepper.disable_axis(Y_AXIS)); - TERN_(DISABLE_INACTIVE_Z, stepper.disable_axis(Z_AXIS)); - TERN_(DISABLE_INACTIVE_I, stepper.disable_axis(I_AXIS)); - TERN_(DISABLE_INACTIVE_J, stepper.disable_axis(J_AXIS)); - TERN_(DISABLE_INACTIVE_K, stepper.disable_axis(K_AXIS)); - TERN_(DISABLE_INACTIVE_U, stepper.disable_axis(U_AXIS)); - TERN_(DISABLE_INACTIVE_V, stepper.disable_axis(V_AXIS)); - TERN_(DISABLE_INACTIVE_W, stepper.disable_axis(W_AXIS)); - TERN_(DISABLE_INACTIVE_E, stepper.disable_e_steppers()); - - TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled()); + // M18 / M84 : Handle steppers inactive time timeout + #if HAS_DISABLE_INACTIVE_AXIS + if (gcode.stepper_inactive_time) { + + static bool already_shutdown_steppers; // = false + + if (!has_blocks && !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 + + // Individual axes will be disabled if configured + TERN_(DISABLE_INACTIVE_X, stepper.disable_axis(X_AXIS)); + TERN_(DISABLE_INACTIVE_Y, stepper.disable_axis(Y_AXIS)); + TERN_(DISABLE_INACTIVE_Z, stepper.disable_axis(Z_AXIS)); + TERN_(DISABLE_INACTIVE_I, stepper.disable_axis(I_AXIS)); + TERN_(DISABLE_INACTIVE_J, stepper.disable_axis(J_AXIS)); + TERN_(DISABLE_INACTIVE_K, stepper.disable_axis(K_AXIS)); + TERN_(DISABLE_INACTIVE_U, stepper.disable_axis(U_AXIS)); + TERN_(DISABLE_INACTIVE_V, stepper.disable_axis(V_AXIS)); + TERN_(DISABLE_INACTIVE_W, stepper.disable_axis(W_AXIS)); + TERN_(DISABLE_INACTIVE_E, stepper.disable_e_steppers()); + + TERN_(AUTO_BED_LEVELING_UBL, bedlevel.steppers_were_disabled()); + } } + else + already_shutdown_steppers = false; } - else - already_shutdown_steppers = false; - } + #endif #if ENABLED(PHOTO_GCODE) && PIN_EXISTS(CHDK) // Check if CHDK should be set to LOW (after M240 set it HIGH) @@ -771,6 +774,10 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { * - Handle Joystick jogging */ void idle(bool no_stepper_sleep/*=false*/) { + #ifdef MAX7219_DEBUG_PROFILE + CodeProfiler idle_profiler; + #endif + #if ENABLED(MARLIN_DEV_MODE) static uint16_t idle_depth = 0; if (++idle_depth > 5) SERIAL_ECHOLNPGM("idle() call depth: ", idle_depth); @@ -780,7 +787,7 @@ void idle(bool no_stepper_sleep/*=false*/) { manage_inactivity(no_stepper_sleep); // Manage Heaters (and Watchdog) - thermalManager.manage_heater(); + thermalManager.task(); // Max7219 heartbeat, animation, etc TERN_(MAX7219_DEBUG, max7219.idle_tasks()); @@ -827,7 +834,7 @@ void idle(bool no_stepper_sleep/*=false*/) { TERN_(PRINTCOUNTER, print_job_timer.tick()); // Update the Beeper queue - TERN_(USE_BEEPER, buzzer.tick()); + TERN_(HAS_BEEPER, buzzer.tick()); // Handle UI input / draw events TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update()); @@ -886,7 +893,7 @@ void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullp // Echo the LCD message to serial for extra context if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNF(lcd_error); } - #if EITHER(HAS_DISPLAY, DWIN_LCD_PROUI) + #if HAS_DISPLAY ui.kill_screen(lcd_error ?: GET_TEXT_F(MSG_KILLED), lcd_component ?: FPSTR(NUL_STR)); #else UNUSED(lcd_error); UNUSED(lcd_component); @@ -930,18 +937,18 @@ void minkill(const bool steppers_off/*=false*/) { // 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(); + hal.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(); + hal.watchdog_refresh(); // Reboot the board hal.reboot(); #else - for (;;) watchdog_refresh(); // Wait for RESET button or power-cycle + for (;;) hal.watchdog_refresh(); // Wait for RESET button or power-cycle #endif } @@ -1237,6 +1244,17 @@ void setup() { SETUP_RUN(tmc_serial_begin()); #endif + #if HAS_TMC_SPI + #if DISABLED(TMC_USE_SW_SPI) + SETUP_RUN(SPI.begin()); + #endif + SETUP_RUN(tmc_init_cs_pins()); + #endif + + #if HAS_L64XX + SETUP_RUN(L64xxManager.init()); // Set up SPI, init drivers + #endif + #if ENABLED(PSU_CONTROL) SETUP_LOG("PSU_CONTROL"); powerManager.init(); @@ -1246,21 +1264,10 @@ void setup() { SETUP_RUN(recovery.setup()); #endif - #if HAS_L64XX - SETUP_RUN(L64xxManager.init()); // Set up SPI, init drivers - #endif - #if HAS_STEPPER_RESET SETUP_RUN(disableStepperDrivers()); #endif - #if HAS_TMC_SPI - #if DISABLED(TMC_USE_SW_SPI) - SETUP_RUN(SPI.begin()); - #endif - SETUP_RUN(tmc_init_cs_pins()); - #endif - SETUP_RUN(hal.init_board()); SETUP_RUN(esp_wifi_init()); @@ -1287,7 +1294,7 @@ void setup() { calibrate_delay_loop(); // Init buzzer pin(s) - #if USE_BEEPER + #if HAS_BEEPER SETUP_RUN(buzzer.init()); #endif @@ -1557,7 +1564,7 @@ void setup() { #endif #if ENABLED(USE_WATCHDOG) - SETUP_RUN(watchdog_init()); // Reinit watchdog after hal.get_reset_source call + SETUP_RUN(hal.watchdog_init()); // Reinit watchdog after hal.get_reset_source call #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) @@ -1573,10 +1580,6 @@ void setup() { SETUP_RUN(hostui.prompt_end()); #endif - #if HAS_TRINAMIC_CONFIG && DISABLED(PSU_DEFAULT_OFF) - SETUP_RUN(test_tmc_connection()); - #endif - #if HAS_DRIVER_SAFE_POWER_PROTECT SETUP_RUN(stepper_driver_backward_report()); #endif @@ -1634,6 +1637,10 @@ void setup() { SETUP_RUN(easythreed_ui.init()); #endif + #if HAS_TRINAMIC_CONFIG && DISABLED(PSU_DEFAULT_OFF) + SETUP_RUN(test_tmc_connection()); + #endif + marlin_state = MF_RUNNING; SETUP_LOG("setup() completed."); diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 7063c7e2de38..f80405a302ee 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -61,6 +61,8 @@ bool printJobOngoing(); bool printingIsPaused(); void startOrResumeJob(); +bool printer_busy(); + extern bool wait_for_heatup; #if HAS_RESUME_CONTINUE diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 14303754820c..72c7e22541f5 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -161,7 +161,7 @@ #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) +#define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct G-code only) #define BOARD_GT2560_V4_A20 1328 // Geeetech GT2560 Rev B for A20(M/T/D) #define BOARD_PROTONEER_CNC_SHIELD_V3 1329 // Mega controller & Protoneer CNC Shield V3.00 #define BOARD_WEEDO_62A 1330 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.) @@ -228,33 +228,33 @@ #define BOARD_RAMPS_14_RE_ARM_EFF 2002 // Re-ARM with RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1) #define BOARD_RAMPS_14_RE_ARM_EEF 2003 // Re-ARM with RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Fan) #define BOARD_RAMPS_14_RE_ARM_SF 2004 // Re-ARM with RAMPS 1.4 (Power outputs: Spindle, Controller Fan) -#define BOARD_MKS_SBASE 2005 // MKS-Sbase (Power outputs: Hotend0, Hotend1, Bed, Fan) +#define BOARD_MKS_SBASE 2005 // MKS-Sbase #define BOARD_AZSMZ_MINI 2006 // AZSMZ Mini -#define BOARD_BIQU_BQ111_A4 2007 // BIQU BQ111-A4 (Power outputs: Hotend, Fan, Bed) -#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_BIQU_BQ111_A4 2007 // BIQU BQ111-A4 +#define BOARD_SELENA_COMPACT 2008 // Selena Compact +#define BOARD_BIQU_B300_V1_0 2009 // BIQU B300_V1.0 +#define BOARD_MKS_SGEN_L 2010 // MKS-SGen-L #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) +#define BOARD_BTT_SKR_V1_1 2012 // BigTreeTech SKR v1.1 +#define BOARD_BTT_SKR_V1_3 2013 // BigTreeTech SKR v1.3 +#define BOARD_BTT_SKR_V1_4 2014 // BigTreeTech SKR v1.4 // // LPC1769 ARM Cortex M3 // -#define BOARD_MKS_SGEN 2500 // MKS-SGen (Power outputs: Hotend0, Hotend1, Bed, Fan) -#define BOARD_AZTEEG_X5_GT 2501 // Azteeg X5 GT (Power outputs: Hotend0, Hotend1, Bed, Fan) -#define BOARD_AZTEEG_X5_MINI 2502 // Azteeg X5 Mini (Power outputs: Hotend0, Bed, Fan) -#define BOARD_AZTEEG_X5_MINI_WIFI 2503 // Azteeg X5 Mini Wifi (Power outputs: Hotend0, Bed, Fan) +#define BOARD_MKS_SGEN 2500 // MKS-SGen +#define BOARD_AZTEEG_X5_GT 2501 // Azteeg X5 GT +#define BOARD_AZTEEG_X5_MINI 2502 // Azteeg X5 Mini +#define BOARD_AZTEEG_X5_MINI_WIFI 2503 // Azteeg X5 Mini Wifi #define BOARD_COHESION3D_REMIX 2504 // Cohesion3D ReMix #define BOARD_COHESION3D_MINI 2505 // Cohesion3D Mini #define BOARD_SMOOTHIEBOARD 2506 // Smoothieboard #define BOARD_TH3D_EZBOARD 2507 // TH3D EZBoard v1.0 -#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) +#define BOARD_BTT_SKR_V1_4_TURBO 2508 // BigTreeTech SKR v1.4 TURBO +#define BOARD_MKS_SGEN_L_V2 2509 // MKS SGEN_L V2 +#define BOARD_BTT_SKR_E3_TURBO 2510 // BigTreeTech SKR E3 Turbo +#define BOARD_FLY_CDY 2511 // FLYmaker FLY CDY // // SAM3X8E ARM Cortex M3 @@ -280,8 +280,8 @@ #define BOARD_RAMPS4DUE_EFF 3017 // RAMPS4DUE (Power outputs: Hotend, Fan0, Fan1) #define BOARD_RAMPS4DUE_EEF 3018 // RAMPS4DUE (Power outputs: Hotend0, Hotend1, Fan) #define BOARD_RAMPS4DUE_SF 3019 // RAMPS4DUE (Power outputs: Spindle, Controller Fan) -#define BOARD_RURAMPS4D_11 3020 // RuRAMPS4Duo v1.1 (Power outputs: Hotend0, Hotend1, Hotend2, Fan0, Fan1, Bed) -#define BOARD_RURAMPS4D_13 3021 // RuRAMPS4Duo v1.3 (Power outputs: Hotend0, Hotend1, Hotend2, Fan0, Fan1, Bed) +#define BOARD_RURAMPS4D_11 3020 // RuRAMPS4Duo v1.1 +#define BOARD_RURAMPS4D_13 3021 // RuRAMPS4Duo v1.3 #define BOARD_ULTRATRONICS_PRO 3022 // ReprapWorld Ultratronics Pro V1.0 #define BOARD_ARCHIM1 3023 // UltiMachine Archim1 (with DRV8825 drivers) #define BOARD_ARCHIM2 3024 // UltiMachine Archim2 (with TMC2130 drivers) @@ -293,7 +293,7 @@ // SAM3X8C ARM Cortex M3 // -#define BOARD_PRINTRBOARD_G2 3100 // PRINTRBOARD G2 +#define BOARD_PRINTRBOARD_G2 3100 // Printrboard G2 #define BOARD_ADSK 3101 // Arduino DUE Shield Kit (ADSK) // @@ -352,19 +352,20 @@ #define BOARD_CREALITY_V431_D 4049 // Creality v4.3.1d (STM32F103RC / STM32F103RE) #define BOARD_CREALITY_V452 4050 // Creality v4.5.2 (STM32F103RC / STM32F103RE) #define BOARD_CREALITY_V453 4051 // Creality v4.5.3 (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V24S1 4052 // Creality v2.4.S1 (STM32F103RC / STM32F103RE) v101 as found in the Ender 7 -#define BOARD_CREALITY_V24S1_301 4053 // Creality v2.4.S1_301 (STM32F103RC / STM32F103RE) as found in the Ender 3 S1 -#define BOARD_TRIGORILLA_PRO 4054 // Trigorilla Pro (STM32F103ZE) -#define BOARD_FLY_MINI 4055 // FLYmaker FLY MINI (STM32F103RC) -#define BOARD_FLSUN_HISPEED 4056 // FLSUN HiSpeedV1 (STM32F103VE) -#define BOARD_BEAST 4057 // STM32F103RE Libmaple-based controller -#define BOARD_MINGDA_MPX_ARM_MINI 4058 // STM32F103ZE Mingda MD-16 -#define BOARD_GTM32_PRO_VD 4059 // STM32F103VE controller -#define BOARD_ZONESTAR_ZM3E2 4060 // Zonestar ZM3E2 (STM32F103RC) -#define BOARD_ZONESTAR_ZM3E4 4061 // Zonestar ZM3E4 V1 (STM32F103VC) -#define BOARD_ZONESTAR_ZM3E4V2 4062 // Zonestar ZM3E4 V2 (STM32F103VC) -#define BOARD_ERYONE_ERY32_MINI 4063 // Eryone Ery32 mini (STM32F103VE) -#define BOARD_PANDA_PI_V29 4064 // Panda Pi V2.9 - Standalone (STM32F103RC) +#define BOARD_CREALITY_V24S1 4052 // Creality v2.4.S1 (STM32F103RC / STM32F103RE) v101 as found in the Ender-7 +#define BOARD_CREALITY_V24S1_301 4053 // Creality v2.4.S1_301 (STM32F103RC / STM32F103RE) v301 as found in the Ender-3 S1 +#define BOARD_CREALITY_V25S1 4054 // Creality v2.5.S1 (STM32F103RE) as found in the CR-10 Smart Pro +#define BOARD_TRIGORILLA_PRO 4055 // Trigorilla Pro (STM32F103ZE) +#define BOARD_FLY_MINI 4056 // FLYmaker FLY MINI (STM32F103RC) +#define BOARD_FLSUN_HISPEED 4057 // FLSUN HiSpeedV1 (STM32F103VE) +#define BOARD_BEAST 4058 // STM32F103RE Libmaple-based controller +#define BOARD_MINGDA_MPX_ARM_MINI 4059 // STM32F103ZE Mingda MD-16 +#define BOARD_GTM32_PRO_VD 4060 // STM32F103VE controller +#define BOARD_ZONESTAR_ZM3E2 4061 // Zonestar ZM3E2 (STM32F103RC) +#define BOARD_ZONESTAR_ZM3E4 4062 // Zonestar ZM3E4 V1 (STM32F103VC) +#define BOARD_ZONESTAR_ZM3E4V2 4063 // Zonestar ZM3E4 V2 (STM32F103VC) +#define BOARD_ERYONE_ERY32_MINI 4064 // Eryone Ery32 mini (STM32F103VE) +#define BOARD_PANDA_PI_V29 4065 // Panda Pi V2.9 - Standalone (STM32F103RC) // // ARM Cortex-M4F @@ -412,11 +413,12 @@ #define BOARD_ANET_ET4P 4232 // ANET ET4P V1.x (STM32F407VG) #define BOARD_FYSETC_CHEETAH_V20 4233 // FYSETC Cheetah V2.0 #define BOARD_TH3D_EZBOARD_V2 4234 // TH3D EZBoard v2.0 -#define BOARD_INDEX_REV03 4235 // Index PnP Controller REV03 (STM32F407VE/VG) +#define BOARD_OPULO_LUMEN_REV3 4235 // Opulo Lumen PnP Controller REV3 (STM32F407VE/VG) #define BOARD_MKS_ROBIN_NANO_V1_3_F4 4236 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) #define BOARD_MKS_EAGLE 4237 // MKS Eagle (STM32F407VE) #define BOARD_ARTILLERY_RUBY 4238 // Artillery Ruby (STM32F401RC) #define BOARD_FYSETC_SPIDER_V2_2 4239 // FYSETC Spider V2.2 (STM32F446VE) +#define BOARD_CREALITY_V24S1_301F4 4240 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4 // // ARM Cortex M7 @@ -426,7 +428,10 @@ #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) +#define BOARD_BTT_SKR_SE_BX_V2 5004 // BigTreeTech SKR SE BX V2.0 (STM32H743II) +#define BOARD_BTT_SKR_SE_BX_V3 5005 // BigTreeTech SKR SE BX V3.0 (STM32H743II) +#define BOARD_BTT_SKR_V3_0 5006 // BigTreeTech SKR V3.0 (STM32H743VG) +#define BOARD_BTT_SKR_V3_0_EZ 5007 // BigTreeTech SKR V3.0 EZ (STM32H743VG) // // Espressif ESP32 WiFi diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 80262d513f38..7f9da909b248 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -67,11 +67,11 @@ #define AXIS_DRIVER_TYPE_V(T) _AXIS_DRIVER_TYPE(V,T) #define AXIS_DRIVER_TYPE_W(T) _AXIS_DRIVER_TYPE(W,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)) -#define AXIS_DRIVER_TYPE_Z2(T) (NUM_Z_STEPPER_DRIVERS >= 2 && _AXIS_DRIVER_TYPE(Z2,T)) -#define AXIS_DRIVER_TYPE_Z3(T) (NUM_Z_STEPPER_DRIVERS >= 3 && _AXIS_DRIVER_TYPE(Z3,T)) -#define AXIS_DRIVER_TYPE_Z4(T) (NUM_Z_STEPPER_DRIVERS >= 4 && _AXIS_DRIVER_TYPE(Z4,T)) +#define AXIS_DRIVER_TYPE_X2(T) (HAS_X2_STEPPER && _AXIS_DRIVER_TYPE(X2,T)) +#define AXIS_DRIVER_TYPE_Y2(T) (HAS_DUAL_Y_STEPPERS && _AXIS_DRIVER_TYPE(Y2,T)) +#define AXIS_DRIVER_TYPE_Z2(T) (NUM_Z_STEPPERS >= 2 && _AXIS_DRIVER_TYPE(Z2,T)) +#define AXIS_DRIVER_TYPE_Z3(T) (NUM_Z_STEPPERS >= 3 && _AXIS_DRIVER_TYPE(Z3,T)) +#define AXIS_DRIVER_TYPE_Z4(T) (NUM_Z_STEPPERS >= 4 && _AXIS_DRIVER_TYPE(Z4,T)) #define AXIS_DRIVER_TYPE_E(N,T) (E_STEPPERS > N && _AXIS_DRIVER_TYPE(E##N,T)) #define AXIS_DRIVER_TYPE_E0(T) AXIS_DRIVER_TYPE_E(0,T) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 16d7b1bf663e..157bd6918515 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -227,10 +227,6 @@ #define STR_PID_DEBUG " PID_DEBUG " #define STR_PID_DEBUG_INPUT ": Input " #define STR_PID_DEBUG_OUTPUT " Output " -#define STR_PID_DEBUG_PTERM " pTerm " -#define STR_PID_DEBUG_ITERM " iTerm " -#define STR_PID_DEBUG_DTERM " dTerm " -#define STR_PID_DEBUG_CTERM " cTerm " #define STR_INVALID_EXTRUDER_NUM " - Invalid extruder number !" #define STR_MPC_AUTOTUNE "MPC Autotune" #define STR_MPC_AUTOTUNE_START " start for " STR_E diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 629486d85f43..09a616456841 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -82,11 +82,11 @@ #define FORCE_INLINE __attribute__((always_inline)) inline #define NO_INLINE __attribute__((noinline)) #define _UNUSED __attribute__((unused)) -#define _O0 __attribute__((optimize("O0"))) -#define _Os __attribute__((optimize("Os"))) -#define _O1 __attribute__((optimize("O1"))) -#define _O2 __attribute__((optimize("O2"))) -#define _O3 __attribute__((optimize("O3"))) +#define __O0 __attribute__((optimize("O0"))) +#define __Os __attribute__((optimize("Os"))) +#define __O1 __attribute__((optimize("O1"))) +#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 @@ -290,7 +290,7 @@ #define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+') #define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+') #define COUNT(a) (sizeof(a)/sizeof(*a)) -#define ZERO(a) memset(a,0,sizeof(a)) +#define ZERO(a) memset((void*)a,0,sizeof(a)) #define COPY(a,b) do{ \ static_assert(sizeof(a[0]) == sizeof(b[0]), "COPY: '" STRINGIFY(a) "' and '" STRINGIFY(b) "' types (sizes) don't match!"); \ memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \ @@ -644,8 +644,8 @@ #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 NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'. +#define _BOOL(x) NOT(NOT(x)) // _BOOL('0') gets '0'. Anything else gets '1'. #define IF_ELSE(TF) _IF_ELSE(_BOOL(TF)) #define _IF_ELSE(TF) _CAT(_IF_, TF) @@ -659,7 +659,6 @@ #define HAS_ARGS(V...) _BOOL(FIRST(_END_OF_ARGUMENTS_ V)()) #define _END_OF_ARGUMENTS_() 0 - // Simple Inline IF Macros, friendly to use in other macro definitions #define IF(O, A, B) ((O) ? (A) : (B)) #define IF_0(O, A) IF(O, A, 0) @@ -712,13 +711,22 @@ #define RREPEAT2_S(S,N,OP,V...) EVAL1024(_RREPEAT2(S,SUB##S(N),OP,V)) #define RREPEAT2(N,OP,V...) RREPEAT2_S(0,N,OP,V) -// See https://github.com/swansontec/map-macro -#define MAP_OUT -#define MAP_END(...) -#define MAP_GET_END() 0, MAP_END -#define MAP_NEXT0(test, next, ...) next MAP_OUT -#define MAP_NEXT1(test, next) MAP_NEXT0 (test, next, 0) -#define MAP_NEXT(test, next) MAP_NEXT1 (MAP_GET_END test, next) -#define MAP0(f, x, peek, ...) f(x) MAP_NEXT (peek, MAP1) (f, peek, __VA_ARGS__) -#define MAP1(f, x, peek, ...) f(x) MAP_NEXT (peek, MAP0) (f, peek, __VA_ARGS__) -#define MAP(f, ...) EVAL512 (MAP1 (f, __VA_ARGS__, (), 0)) +// Call OP(A) with each item as an argument +#define _MAP(_MAP_OP,A,V...) \ + _MAP_OP(A) \ + IF_ELSE(HAS_ARGS(V)) \ + ( DEFER2(__MAP)()(_MAP_OP,V) ) \ + ( /* Do nothing */ ) +#define __MAP() _MAP + +#define MAP(OP,V...) EVAL(_MAP(OP,V)) + +// Emit a list of OP(A) with the given items +#define _MAPLIST(_MAP_OP,A,V...) \ + _MAP_OP(A) \ + IF_ELSE(HAS_ARGS(V)) \ + ( , DEFER2(__MAPLIST)()(_MAP_OP,V) ) \ + ( /* Do nothing */ ) +#define __MAPLIST() _MAPLIST + +#define MAPLIST(OP,V...) EVAL(_MAPLIST(OP,V)) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index a605a6f02441..05a713e435de 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -45,6 +45,7 @@ typedef const char Language_Str[]; // Set unused languages equal to each other so the // compiler can optimize away the conditionals. +#define LCD_LANGUAGE_1 LCD_LANGUAGE #ifndef LCD_LANGUAGE_2 #define LCD_LANGUAGE_2 LCD_LANGUAGE #endif diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 140a031b7756..727b191d0404 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -30,12 +30,15 @@ uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE; // Commonly-used strings in serial output -PGMSTR(NUL_STR, ""); PGMSTR(SP_P_STR, " P"); PGMSTR(SP_T_STR, " T"); -PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); -LOGICAL_AXIS_CODE(PGMSTR(SP_E_STR, " E"), PGMSTR(SP_X_STR, " X"), PGMSTR(SP_Y_STR, " Y"), PGMSTR(SP_Z_STR, " Z"), PGMSTR(SP_I_STR, " " STR_I), PGMSTR(SP_J_STR, " " STR_J), PGMSTR(SP_K_STR, " " STR_K), PGMSTR(SP_U_STR, " " STR_U), PGMSTR(SP_V_STR, " " STR_V), PGMSTR(SP_W_STR, " " STR_W)); -LOGICAL_AXIS_CODE(PGMSTR(SP_E_LBL, " E:"), PGMSTR(SP_X_LBL, " X:"), PGMSTR(SP_Y_LBL, " Y:"), PGMSTR(SP_Z_LBL, " Z:"), PGMSTR(SP_I_LBL, " " STR_I ":"), PGMSTR(SP_J_LBL, " " STR_J ":"), PGMSTR(SP_K_LBL, " " STR_K ":"), PGMSTR(SP_U_LBL, " " STR_U ":"), PGMSTR(SP_V_LBL, " " STR_V ":"), PGMSTR(SP_W_LBL, " " STR_W ":")); -LOGICAL_AXIS_CODE(PGMSTR(E_STR, "E"), PGMSTR(X_STR, "X"), PGMSTR(Y_STR, "Y"), PGMSTR(Z_STR, "Z"), PGMSTR(I_STR, STR_I), PGMSTR(J_STR, STR_J), PGMSTR(K_STR, STR_K), PGMSTR(U_STR, STR_U), PGMSTR(V_STR, STR_V), PGMSTR(W_STR, STR_W)); -LOGICAL_AXIS_CODE(PGMSTR(E_LBL, "E:"), PGMSTR(X_LBL, "X:"), PGMSTR(Y_LBL, "Y:"), PGMSTR(Z_LBL, "Z:"), PGMSTR(I_LBL, STR_I ":"), PGMSTR(J_LBL, STR_J ":"), PGMSTR(K_LBL, STR_K ":"), PGMSTR(U_LBL, STR_U ":"), PGMSTR(V_LBL, STR_V ":"), PGMSTR(W_LBL, STR_W ":")); +PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); +PGMSTR(SP_P_STR, " P"); PGMSTR(SP_T_STR, " T"); PGMSTR(NUL_STR, ""); + +#define _N_STR(N) PGMSTR(N##_STR, STR_##N); +#define _N_LBL(N) PGMSTR(N##_LBL, STR_##N ":"); +#define _SP_N_STR(N) PGMSTR(SP_##N##_STR, " " STR_##N); +#define _SP_N_LBL(N) PGMSTR(SP_##N##_LBL, " " STR_##N ":"); +MAP(_N_STR, LOGICAL_AXIS_NAMES); MAP(_SP_N_STR, LOGICAL_AXIS_NAMES); +MAP(_N_LBL, LOGICAL_AXIS_NAMES); MAP(_SP_N_LBL, LOGICAL_AXIS_NAMES); // Hook Meatpack if it's enabled on the first leaf #if ENABLED(MEATPACK_ON_SERIAL_PORT_1) @@ -69,8 +72,8 @@ void serial_print_P(PGM_P str) { while (const char c = pgm_read_byte(str++)) SERIAL_CHAR(c); } -void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serial_print_P(echomagic); } -void serial_error_start() { static PGMSTR(errormagic, "Error:"); serial_print_P(errormagic); } +void serial_echo_start() { serial_print(F("echo:")); } +void serial_error_start() { serial_print(F("Error:")); } void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); } diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 000e2060c532..c19bc087833d 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -28,17 +28,6 @@ #include "../feature/meatpack.h" #endif -// Commonly-used strings in serial output -extern const char NUL_STR[], SP_P_STR[], SP_T_STR[], - SP_A_STR[], SP_B_STR[], SP_C_STR[], - LOGICAL_AXIS_LIST(SP_E_STR[], SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_I_STR[], SP_J_STR[], SP_K_STR[], SP_U_STR[], SP_V_STR[], SP_W_STR[]), - LOGICAL_AXIS_LIST(SP_E_LBL[], SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_I_LBL[], SP_J_LBL[], SP_K_LBL[], SP_U_LBL[], SP_V_LBL[], SP_W_LBL[]), - LOGICAL_AXIS_LIST(E_STR[], X_STR[], Y_STR[], Z_STR[], I_STR[], J_STR[], K_STR[], U_STR[], V_STR[], W_STR[]), - LOGICAL_AXIS_LIST(E_LBL[], X_LBL[], Y_LBL[], Z_LBL[], I_LBL[], J_LBL[], K_LBL[], U_LBL[], V_LBL[], W_LBL[]); - -PGM_P const SP_AXIS_LBL[] PROGMEM = LOGICAL_AXIS_ARRAY(SP_E_LBL, SP_X_LBL, SP_Y_LBL, SP_Z_LBL, SP_I_LBL, SP_J_LBL, SP_K_LBL, SP_U_LBL, SP_V_LBL, SP_W_LBL); -PGM_P const SP_AXIS_STR[] PROGMEM = LOGICAL_AXIS_ARRAY(SP_E_STR, SP_X_STR, SP_Y_STR, SP_Z_STR, SP_I_STR, SP_J_STR, SP_K_STR, SP_U_STR, SP_V_STR, SP_W_STR); - // // Debugging flags for use by M111 // @@ -354,3 +343,32 @@ inline void print_pos(const xyz_pos_t &xyz, FSTR_P const prefix=nullptr, FSTR_P #define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, F(" " STRINGIFY(VAR) "="), F(" : " SUFFIX "\n")); }while(0) #define SERIAL_XYZ(PREFIX,V...) do { print_pos(V, F(PREFIX)); }while(0) + +// +// Commonly-used strings in serial output +// + +#define _N_STR(N) N##_STR +#define _N_LBL(N) N##_LBL +#define _N_STR_A(N) _N_STR(N)[] +#define _N_LBL_A(N) _N_LBL(N)[] +#define _SP_N_STR(N) SP_##N##_STR +#define _SP_N_LBL(N) SP_##N##_LBL +#define _SP_N_STR_A(N) _SP_N_STR(N)[] +#define _SP_N_LBL_A(N) _SP_N_LBL(N)[] + +extern const char SP_A_STR[], SP_B_STR[], SP_C_STR[], SP_P_STR[], SP_T_STR[], NUL_STR[], + MAPLIST(_N_STR_A, LOGICAL_AXIS_NAMES), MAPLIST(_SP_N_STR_A, LOGICAL_AXIS_NAMES), + MAPLIST(_N_LBL_A, LOGICAL_AXIS_NAMES), MAPLIST(_SP_N_LBL_A, LOGICAL_AXIS_NAMES); + +PGM_P const SP_AXIS_LBL[] PROGMEM = { MAPLIST(_SP_N_LBL, LOGICAL_AXIS_NAMES) }; +PGM_P const SP_AXIS_STR[] PROGMEM = { MAPLIST(_SP_N_STR, LOGICAL_AXIS_NAMES) }; + +#undef _N_STR +#undef _N_LBL +#undef _N_STR_A +#undef _N_LBL_A +#undef _SP_N_STR +#undef _SP_N_LBL +#undef _SP_N_STR_A +#undef _SP_N_LBL_A diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index 2e3c31b2085a..65c553c70259 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -300,7 +300,7 @@ struct MultiSerial : public SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) // 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 +#if HAS_MULTI_SERIAL #define Serial2Class ConditionalSerial #if NUM_SERIAL >= 3 #define Serial3Class ConditionalSerial diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index dace435fd14d..335aa3a33449 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -39,20 +39,28 @@ struct IF { typedef L type; }; #define NUM_AXIS_GANG(V...) GANG_N(NUM_AXES, V) #define NUM_AXIS_CODE(V...) CODE_N(NUM_AXES, V) #define NUM_AXIS_LIST(V...) LIST_N(NUM_AXES, V) +#define NUM_AXIS_LIST_1(V) LIST_N_1(NUM_AXES, V) #define NUM_AXIS_ARRAY(V...) { NUM_AXIS_LIST(V) } +#define NUM_AXIS_ARRAY_1(V) { NUM_AXIS_LIST_1(V) } #define NUM_AXIS_ARGS(T...) NUM_AXIS_LIST(T x, T y, T z, T i, T j, T k, T u, T v, T w) #define NUM_AXIS_ELEM(O) NUM_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) #define NUM_AXIS_DEFS(T,V) NUM_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V, T u=V, T v=V, T w=V) +#define MAIN_AXIS_NAMES NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W) +#define MAIN_AXIS_MAP(F) MAP(F, MAIN_AXIS_NAMES) +#define STR_AXES_MAIN NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W) #define LOGICAL_AXIS_GANG(E,V...) NUM_AXIS_GANG(V) GANG_ITEM_E(E) #define LOGICAL_AXIS_CODE(E,V...) NUM_AXIS_CODE(V) CODE_ITEM_E(E) #define LOGICAL_AXIS_LIST(E,V...) NUM_AXIS_LIST(V) LIST_ITEM_E(E) +#define LOGICAL_AXIS_LIST_1(V) NUM_AXIS_LIST_1(V) LIST_ITEM_E(V) #define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) } +#define LOGICAL_AXIS_ARRAY_1(V) { LOGICAL_AXIS_LIST_1(V) } #define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k, T u, T v, T w) #define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) #define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V, T u=V, T v=V, T w=V) - -#define LOGICAL_AXES_STRING LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W) +#define LOGICAL_AXIS_NAMES LOGICAL_AXIS_LIST(E, X, Y, Z, I, J, K, U, V, W) +#define LOGICAL_AXIS_MAP(F) MAP(F, LOGICAL_AXIS_NAMES) +#define STR_AXES_LOGICAL LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W) #define XYZ_GANG(V...) GANG_N(PRIMARY_LINEAR_AXES, V) #define XYZ_CODE(V...) CODE_N(PRIMARY_LINEAR_AXES, V) @@ -91,8 +99,8 @@ struct Flags { void set(const int n) { b |= (bits_t)_BV(n); } void clear(const int n) { b &= ~(bits_t)_BV(n); } bool test(const int n) const { return TEST(b, n); } - bool operator[](const int n) { return test(n); } - bool operator[](const int n) const { return test(n); } + const bool operator[](const int n) { return test(n); } + const bool operator[](const int n) const { return test(n); } int size() const { return sizeof(b); } }; @@ -105,8 +113,8 @@ struct Flags<1> { void set(const int) { b = true; } void clear(const int) { b = false; } bool test(const int) const { return b; } - bool operator[](const int) { return b; } - bool operator[](const int) const { return b; } + bool& operator[](const int) { return b; } + bool operator[](const int) const { return b; } int size() const { return sizeof(b); } }; @@ -173,7 +181,6 @@ enum AxisEnum : uint8_t { }; typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t; -typedef IF<(NUM_AXES > 8), uint16_t, uint8_t>::type linear_axis_bits_t; // // Loop over axes diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 658ed6cd81a5..9cdf8dec7bcf 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -29,10 +29,10 @@ void safe_delay(millis_t ms) { while (ms > 50) { ms -= 50; delay(50); - thermalManager.manage_heater(); + thermalManager.task(); } delay(ms); - thermalManager.manage_heater(); // This keeps us safe if too many small safe_delay() calls are made + thermalManager.task(); // This keeps us safe if too many small safe_delay() calls are made } // A delay to provide brittle hosts time to receive bytes @@ -132,11 +132,10 @@ void safe_delay(millis_t ms) { #else #if ENABLED(AUTO_BED_LEVELING_UBL) SERIAL_ECHOPGM("UBL Adjustment Z"); - const float rz = ubl.get_z_correction(current_position); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) SERIAL_ECHOPGM("ABL Adjustment Z"); - const float rz = bbl.get_z_correction(current_position); #endif + const float rz = bedlevel.get_z_correction(current_position); SERIAL_ECHO(ftostr43sign(rz, '+')); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (planner.z_fade_height) { @@ -156,11 +155,13 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM("Mesh Bed Leveling"); if (planner.leveling_active) { SERIAL_ECHOLNPGM(" (enabled)"); - SERIAL_ECHOPGM("MBL Adjustment Z", ftostr43sign(mbl.get_z(current_position), '+')); + const float z_offset = bedlevel.get_z_offset(), + z_correction = bedlevel.get_z_correction(current_position); + SERIAL_ECHOPGM("MBL Adjustment Z", ftostr43sign(z_offset + z_correction, '+')); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (planner.z_fade_height) { SERIAL_ECHOPGM(" (", ftostr43sign( - mbl.get_z(current_position, planner.fade_scaling_factor_for_z(current_position.z)), '+' + z_offset + z_correction * planner.fade_scaling_factor_for_z(current_position.z), '+' )); SERIAL_CHAR(')'); } diff --git a/Marlin/src/feature/adc/adc_mcp3426.cpp b/Marlin/src/feature/adc/adc_mcp3426.cpp index aaddf46821b0..49bb67ef6d5c 100644 --- a/Marlin/src/feature/adc/adc_mcp3426.cpp +++ b/Marlin/src/feature/adc/adc_mcp3426.cpp @@ -34,7 +34,7 @@ #include "adc_mcp3426.h" // Read the ADC value from MCP342X on a specific channel -int16_t MCP3426::ReadValue(uint8_t channel, uint8_t gain) { +int16_t MCP3426::ReadValue(uint8_t channel, uint8_t gain, uint8_t address) { Error = false; #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) @@ -44,7 +44,7 @@ int16_t MCP3426::ReadValue(uint8_t channel, uint8_t gain) { Wire.begin(); // No address joins the BUS as the master - Wire.beginTransmission(I2C_ADDRESS(MCP342X_ADC_I2C_ADDRESS)); + Wire.beginTransmission(I2C_ADDRESS(address)); // Continuous Conversion Mode, 16 bit, Channel 1, Gain x4 // 26 = 0b00011000 @@ -75,7 +75,7 @@ int16_t MCP3426::ReadValue(uint8_t channel, uint8_t gain) { uint8_t buffer[len] = {}; do { - Wire.requestFrom(I2C_ADDRESS(MCP342X_ADC_I2C_ADDRESS), len); + Wire.requestFrom(I2C_ADDRESS(address), len); if (Wire.available() != len) { Error = true; return 0; diff --git a/Marlin/src/feature/adc/adc_mcp3426.h b/Marlin/src/feature/adc/adc_mcp3426.h index 35458716b975..af48593369e1 100644 --- a/Marlin/src/feature/adc/adc_mcp3426.h +++ b/Marlin/src/feature/adc/adc_mcp3426.h @@ -29,12 +29,9 @@ #include #include -// Address of MCP342X chip -#define MCP342X_ADC_I2C_ADDRESS 104 - class MCP3426 { public: - int16_t ReadValue(uint8_t channel, uint8_t gain); + int16_t ReadValue(uint8_t channel, uint8_t gain, uint8_t address); bool Error; }; diff --git a/Marlin/src/feature/bedlevel/abl/bbl.cpp b/Marlin/src/feature/bedlevel/abl/bbl.cpp index 9dcd66912893..be0e862cc16a 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.cpp +++ b/Marlin/src/feature/bedlevel/abl/bbl.cpp @@ -35,7 +35,7 @@ #include "../../../lcd/extui/ui_api.h" #endif -LevelingBilinear bbl; +LevelingBilinear bedlevel; xy_pos_t LevelingBilinear::grid_spacing, LevelingBilinear::grid_start; @@ -258,8 +258,8 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* ); } } -#endif // ABL_BILINEAR_SUBDIVISION +#endif // ABL_BILINEAR_SUBDIVISION // Refresh after other values have been updated void LevelingBilinear::refresh_bed_level() { diff --git a/Marlin/src/feature/bedlevel/abl/bbl.h b/Marlin/src/feature/bedlevel/abl/bbl.h index 86da5aea1075..c2be4fee821c 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.h +++ b/Marlin/src/feature/bedlevel/abl/bbl.h @@ -24,9 +24,12 @@ #include "../../../inc/MarlinConfigPre.h" class LevelingBilinear { +public: + static bed_mesh_t z_values; static xy_pos_t grid_spacing, grid_start; + +private: static xy_float_t grid_factor; - static bed_mesh_t z_values; static xy_pos_t cached_rel; static xy_int8_t cached_g; @@ -53,20 +56,15 @@ class LevelingBilinear { static void print_leveling_grid(const bed_mesh_t* _z_values = NULL); static void refresh_bed_level(); static bool has_mesh() { return !!grid_spacing.x; } - static bed_mesh_t& get_z_values() { return z_values; } - static const xy_pos_t& get_grid_spacing() { return grid_spacing; } - static const xy_pos_t& get_grid_start() { return grid_start; } - static float get_mesh_x(int16_t i) { return grid_start.x + i * grid_spacing.x; } - static float get_mesh_y(int16_t j) { return grid_start.y + j * grid_spacing.y; } + static bool mesh_is_valid() { return has_mesh(); } + static float get_mesh_x(const uint8_t i) { return grid_start.x + i * grid_spacing.x; } + static float get_mesh_y(const uint8_t j) { return grid_start.y + j * grid_spacing.y; } static float get_z_correction(const xy_pos_t &raw); + static constexpr float get_z_offset() { return 0.0f; } #if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES) static void line_to_destination(const_feedRate_t scaled_fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF); #endif }; -extern LevelingBilinear bbl; - -#define _GET_MESH_X(I) bbl.get_mesh_x(I) -#define _GET_MESH_Y(J) bbl.get_mesh_y(J) -#define Z_VALUES_ARR bbl.get_z_values() +extern LevelingBilinear bedlevel; diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index 2405905d4e65..1ca9696a3a30 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -47,14 +47,11 @@ #endif bool leveling_is_valid() { - return TERN1(MESH_BED_LEVELING, mbl.has_mesh()) - && TERN1(AUTO_BED_LEVELING_BILINEAR, bbl.has_mesh()) - && TERN1(AUTO_BED_LEVELING_UBL, ubl.mesh_is_valid()); + return TERN1(HAS_MESH, bedlevel.mesh_is_valid()); } /** - * Turn bed leveling on or off, fixing the current - * position as-needed. + * Turn bed leveling on or off, correcting the current position. * * Disable: Current position = physical position * Enable: Current position = "unleveled" physical position @@ -65,24 +62,25 @@ void set_bed_leveling_enabled(const bool enable/*=true*/) { if (can_change && enable != planner.leveling_active) { + auto _report_leveling = []{ + if (DEBUGGING(LEVELING)) { + if (planner.leveling_active) + DEBUG_POS("Leveling ON", current_position); + else + DEBUG_POS("Leveling OFF", current_position); + } + }; + + _report_leveling(); planner.synchronize(); - if (planner.leveling_active) { // leveling from on to off - if (DEBUGGING(LEVELING)) DEBUG_POS("Leveling ON", current_position); - // change unleveled current_position to physical current_position without moving steppers. - planner.apply_leveling(current_position); - planner.leveling_active = false; // disable only AFTER calling apply_leveling - if (DEBUGGING(LEVELING)) DEBUG_POS("...Now OFF", current_position); - } - else { // leveling from off to on - if (DEBUGGING(LEVELING)) DEBUG_POS("Leveling OFF", current_position); - planner.leveling_active = true; // enable BEFORE calling unapply_leveling, otherwise ignored - // change physical current_position to unleveled current_position without moving steppers. - planner.unapply_leveling(current_position); - if (DEBUGGING(LEVELING)) DEBUG_POS("...Now ON", current_position); - } + // Get the corrected leveled / unleveled position + planner.apply_modifiers(current_position); // Physical position with all modifiers + planner.leveling_active ^= true; // Toggle leveling between apply and unapply + planner.unapply_modifiers(current_position); // Logical position with modifiers removed sync_plan_position(); + _report_leveling(); } } @@ -116,18 +114,9 @@ TemporaryBedLevelingState::TemporaryBedLevelingState(const bool enable) : saved( */ void reset_bed_level() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("reset_bed_level"); - #if ENABLED(AUTO_BED_LEVELING_UBL) - ubl.reset(); - #else - set_bed_leveling_enabled(false); - #if ENABLED(MESH_BED_LEVELING) - mbl.reset(); - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - bbl.reset(); - #elif ABL_PLANAR - planner.bed_level_matrix.set_to_identity(); - #endif - #endif + IF_DISABLED(AUTO_BED_LEVELING_UBL, set_bed_leveling_enabled(false)); + TERN_(HAS_MESH, bedlevel.reset()); + TERN_(ABL_PLANAR, planner.bed_level_matrix.set_to_identity()); } #if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index f295da1d037a..aeafec10d6ab 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -69,9 +69,6 @@ class TemporaryBedLevelingState { #include "mbl/mesh_bed_leveling.h" #endif - #define Z_VALUES(X,Y) Z_VALUES_ARR[X][Y] - #define _GET_MESH_POS(M) { _GET_MESH_X(M.a), _GET_MESH_Y(M.b) } - #if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) #include @@ -92,7 +89,7 @@ class TemporaryBedLevelingState { bool valid() const { return pos.x >= 0 && pos.y >= 0; } #if ENABLED(AUTO_BED_LEVELING_UBL) xy_pos_t meshpos() { - return { ubl.mesh_index_to_xpos(pos.x), ubl.mesh_index_to_ypos(pos.y) }; + return { bedlevel.get_mesh_x(pos.x), bedlevel.get_mesh_y(pos.y) }; } #endif operator xy_int8_t&() { return pos; } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp index fbc3f2785e14..193cbbf7654a 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp @@ -32,7 +32,7 @@ #include "../../../lcd/extui/ui_api.h" #endif - mesh_bed_leveling mbl; + mesh_bed_leveling bedlevel; float mesh_bed_leveling::z_offset, mesh_bed_leveling::z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y], diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index 06fae16c21e9..1a8e693e8180 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -34,9 +34,6 @@ enum MeshLevelingState : char { #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 class mesh_bed_leveling { public: @@ -56,6 +53,8 @@ class mesh_bed_leveling { return false; } + static bool mesh_is_valid() { return has_mesh(); } + static void set_z(const int8_t px, const int8_t py, const_float_t z) { z_values[px][py] = z; } static void zigzag(const int8_t index, int8_t &px, int8_t &py) { @@ -70,6 +69,9 @@ class mesh_bed_leveling { set_z(px, py, z); } + static float get_mesh_x(const uint8_t i) { return index_to_xpos[i]; } + static float get_mesh_y(const uint8_t i) { return index_to_ypos[i]; } + static int8_t cell_index_x(const_float_t x) { int8_t cx = (x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST); return constrain(cx, 0, GRID_MAX_CELLS_X - 1); @@ -102,12 +104,9 @@ class mesh_bed_leveling { return z1 + delta_a * delta_z; } - static float get_z(const xy_pos_t &pos - OPTARG(ENABLE_LEVELING_FADE_HEIGHT, const_float_t factor=1.0f) - ) { - #if DISABLED(ENABLE_LEVELING_FADE_HEIGHT) - constexpr float factor = 1.0f; - #endif + static float get_z_offset() { return z_offset; } + + static float get_z_correction(const xy_pos_t &pos) { const xy_int8_t ind = cell_indexes(pos); const 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], @@ -115,7 +114,7 @@ class mesh_bed_leveling { 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 + zf * factor; + return zf; } #if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES) @@ -123,4 +122,4 @@ class mesh_bed_leveling { #endif }; -extern mesh_bed_leveling mbl; +extern mesh_bed_leveling bedlevel; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index c162062f8609..2aa50be34d26 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -26,7 +26,7 @@ #include "../bedlevel.h" -unified_bed_leveling ubl; +unified_bed_leveling bedlevel; #include "../../../MarlinCore.h" #include "../../../gcode/gcode.h" diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index f117c1af65d3..a7103d6e18c4 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -70,20 +70,19 @@ class unified_bed_leveling { 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; + 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 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 probe_entire_mesh(const xy_pos_t &near, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) __O0; static void tilt_mesh_based_on_3pts(const_float_t z1, const_float_t z2, const_float_t z3); static void tilt_mesh_based_on_probed_grid(const bool do_ubl_mesh_map); static bool smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir); static bool smart_fill_one(const xy_uint8_t &pos, const xy_uint8_t &dir) { 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(); @@ -98,17 +97,18 @@ class unified_bed_leveling { 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 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 smart_fill_mesh(); - 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 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; @@ -215,7 +215,7 @@ class unified_bed_leveling { return _UBL_OUTER_Z_RAISE; } - const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * RECIPROCAL(MESH_X_DIST), + const float xratio = (rx0 - get_mesh_x(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 @@ -238,7 +238,7 @@ class unified_bed_leveling { return _UBL_OUTER_Z_RAISE; } - const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * RECIPROCAL(MESH_Y_DIST), + const float yratio = (ry0 - get_mesh_y(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 @@ -264,16 +264,17 @@ class unified_bed_leveling { return UBL_Z_RAISE_WHEN_OFF_MESH; #endif - 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); + const uint8_t mx = _MIN(cx, (GRID_MAX_POINTS_X) - 2) + 1, my = _MIN(cy, (GRID_MAX_POINTS_Y) - 2) + 1, + x0 = get_mesh_x(cx), x1 = get_mesh_x(cx + 1); + const float z1 = calc_z0(rx0, x0, z_values[cx][cy], x1, z_values[mx][cy]), + z2 = calc_z0(rx0, x0, z_values[cx][my], x1, z_values[mx][my]); + float z0 = calc_z0(ry0, get_mesh_y(cy), z1, get_mesh_y(cy + 1), z2); - 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 (isnan(z0)) { // If part of the Mesh is undefined, it will show up as NAN + z0 = 0.0; // in 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 + // needed to complete the height correction. if (DEBUGGING(MESH_ADJUST)) DEBUG_ECHOLNPGM("??? Yikes! NAN in "); } @@ -287,10 +288,12 @@ class unified_bed_leveling { } static float get_z_correction(const xy_pos_t &pos) { return get_z_correction(pos.x, pos.y); } - static float mesh_index_to_xpos(const uint8_t i) { + static constexpr float get_z_offset() { return 0.0f; } + + static float get_mesh_x(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 float mesh_index_to_ypos(const uint8_t i) { + static float get_mesh_y(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); } @@ -307,11 +310,7 @@ class unified_bed_leveling { }; // class unified_bed_leveling -extern unified_bed_leveling ubl; - -#define _GET_MESH_X(I) ubl.mesh_index_to_xpos(I) -#define _GET_MESH_Y(J) ubl.mesh_index_to_ypos(J) -#define Z_VALUES_ARR ubl.z_values +extern unified_bed_leveling bedlevel; // Prevent debugging propagating to other files #include "../../../core/debug_out.h" diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 0ae3e301ccbb..a02918ff297e 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -763,6 +763,7 @@ void unified_bed_leveling::shift_mesh_height() { TERN_(HAS_MARLINUI_MENU, ui.capture()); TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); + TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart()); save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained uint8_t count = GRID_MAX_POINTS; @@ -826,6 +827,7 @@ void unified_bed_leveling::shift_mesh_height() { ); TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); + TERN_(DWIN_LCD_PROUI, DWIN_LevelingDone()); } #endif // HAS_BED_PROBE @@ -939,11 +941,7 @@ void set_message_with_feedback(FSTR_P const fstr) { // 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 - }; + const xyz_pos_t ppos = { get_mesh_x(lpos.x), get_mesh_y(lpos.y), z_clearance }; if (!position_is_reachable(ppos)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) @@ -1038,11 +1036,7 @@ void set_message_with_feedback(FSTR_P const fstr) { 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 - }; + const xyz_pos_t raw = { get_mesh_x(lpos.x), get_mesh_y(lpos.y), Z_CLEARANCE_BETWEEN_PROBES }; if (!position_is_reachable(raw)) break; // SHOULD NOT OCCUR (find_closest_mesh_point_of_type only returns reachable) @@ -1275,7 +1269,7 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { 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))) + if (!probe.can_reach(get_mesh_x(i), get_mesh_y(j))) continue; found_a_NAN = true; @@ -1327,11 +1321,11 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { 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) + if ( d->type == CLOSEST || d->type == (isnan(bedlevel.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) }; + const xy_pos_t mpos = { bedlevel.get_mesh_x(i), bedlevel.get_mesh_y(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. @@ -1375,7 +1369,7 @@ mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const Mesh || (type == SET_IN_BITMAP && !done_flags->marked(i, j)) ) { // Found a Mesh Point of the specified type! - const xy_pos_t mpos = { mesh_index_to_xpos(i), mesh_index_to_ypos(j) }; + const xy_pos_t mpos = { get_mesh_x(i), get_mesh_y(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. @@ -1431,10 +1425,10 @@ 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 + 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)) { @@ -1623,9 +1617,7 @@ void unified_bed_leveling::smart_fill_mesh() { 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]; + float mx = get_mesh_x(i), my = get_mesh_y(j), mz = z_values[i][j]; if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR_F("before rotation = [", mx, 7); @@ -1722,18 +1714,18 @@ void unified_bed_leveling::smart_fill_mesh() { xy_pos_t ppos; LOOP_L_N(ix, GRID_MAX_POINTS_X) { - ppos.x = mesh_index_to_xpos(ix); + ppos.x = get_mesh_x(ix); LOOP_L_N(iy, GRID_MAX_POINTS_Y) { - ppos.y = mesh_index_to_ypos(iy); + ppos.y = get_mesh_y(iy); if (isnan(z_values[ix][iy])) { // undefined mesh point at (ppos.x,ppos.y), compute weighted LSF from original valid mesh points. incremental_LSF_reset(&lsf_results); xy_pos_t rpos; LOOP_L_N(jx, GRID_MAX_POINTS_X) { - rpos.x = mesh_index_to_xpos(jx); + rpos.x = get_mesh_x(jx); LOOP_L_N(jy, GRID_MAX_POINTS_Y) { if (TEST(bitmap[jx], jy)) { - rpos.y = mesh_index_to_ypos(jy); + rpos.y = get_mesh_y(jy); const float rz = z_values[jx][jy], w = 1.0f + weight_scaled / (rpos - ppos).magnitude(); incremental_WLSF(&lsf_results, rpos, rz, w); @@ -1792,7 +1784,7 @@ void unified_bed_leveling::smart_fill_mesh() { 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_ECHO_F(LOGICAL_X_POSITION(get_mesh_x(i)), 3); SERIAL_ECHOPGM(" "); serial_delay(25); } @@ -1800,7 +1792,7 @@ void unified_bed_leveling::smart_fill_mesh() { 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_ECHO_F(LOGICAL_Y_POSITION(get_mesh_y(i)), 3); SERIAL_ECHOPGM(" "); serial_delay(25); } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index f7e98c9fa77d..9fa2257dc8a6 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -36,8 +36,18 @@ #include "../../../MarlinCore.h" #include +//#define DEBUG_UBL_MOTION +#define DEBUG_OUT ENABLED(DEBUG_UBL_MOTION) +#include "../../../core/debug_out.h" + #if !UBL_SEGMENTED + // TODO: The first and last parts of a move might result in very short segment(s) + // after getting split on the cell boundary, so moves like that should not + // get split. This will be most common for moves that start/end near the + // corners of cells. To fix the issue, simply check if the start/end of the line + // is very close to a cell boundary in advance and don't split the line there. + 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 @@ -76,8 +86,8 @@ #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), - yratio = (end.y - mesh_index_to_ypos(iend.y)) * RECIPROCAL(MESH_Y_DIST), + const float xratio = (end.x - get_mesh_x(iend.x)) * RECIPROCAL(MESH_X_DIST), + yratio = (end.y - get_mesh_y(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]); @@ -139,7 +149,7 @@ icell.y += ineg.y; // Line going down? Just go to the bottom. while (icell.y != iend.y + ineg.y) { icell.y += iadd.y; - const float next_mesh_line_y = mesh_index_to_ypos(icell.y); + const float next_mesh_line_y = get_mesh_y(icell.y); /** * Skip the calculations for an infinite slope. @@ -155,7 +165,7 @@ // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; - dest.y = mesh_index_to_ypos(icell.y); + dest.y = get_mesh_y(icell.y); /** * Without this check, it's possible to generate a zero length move, as in the case where @@ -176,7 +186,9 @@ dest.z += z0; planner.buffer_segment(dest, scaled_fr_mm_s, extruder); - } //else printf("FIRST MOVE PRUNED "); + } + else + DEBUG_ECHOLNPGM("[ubl] skip Y segment"); } // At the final destination? Usually not, but when on a Y Mesh Line it's completed. @@ -196,7 +208,7 @@ while (icell.x != iend.x + ineg.x) { icell.x += iadd.x; - dest.x = mesh_index_to_xpos(icell.x); + dest.x = get_mesh_x(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(dest.y, icell.x, icell.y) @@ -225,7 +237,9 @@ dest.z += z0; if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; - } //else printf("FIRST MOVE PRUNED "); + } + else + DEBUG_ECHOLNPGM("[ubl] skip Y segment"); } if (xy_pos_t(current_position) != xy_pos_t(end)) @@ -245,8 +259,8 @@ 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); + const float next_mesh_line_x = get_mesh_x(icell.x + iadd.x), + next_mesh_line_y = get_mesh_y(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 @@ -340,7 +354,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 @@ -423,7 +437,7 @@ if (isnan(z_x0y1)) z_x0y1 = 0; // in order to avoid isnan tests per cell, if (isnan(z_x1y1)) z_x1y1 = 0; // thus guessing zero for undefined points - const xy_pos_t pos = { mesh_index_to_xpos(icell.x), mesh_index_to_ypos(icell.y) }; + const xy_pos_t pos = { get_mesh_x(icell.x), get_mesh_y(icell.y) }; xy_pos_t cell = raw - pos; const float z_xmy0 = (z_x1y0 - z_x0y0) * RECIPROCAL(MESH_X_DIST), // z slope per x along y0 (lower left to lower right) @@ -450,10 +464,7 @@ if (--segments == 0) raw = destination; // if this is last segment, use destination for exact const float z_cxcy = (z_cxy0 + z_cxym * cell.y) // interpolated mesh z height along cell.x at cell.y - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - * fade_scaling_factor // apply fade factor to interpolated mesh height - #endif - ; + TERN_(ENABLE_LEVELING_FADE_HEIGHT, * fade_scaling_factor); // apply fade factor to interpolated height 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) ); diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index d911fae6ae75..10d3131aedcb 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -45,7 +45,7 @@ void stop(); bool BLTouch::command(const BLTCommand cmd, const millis_t &ms) { if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("BLTouch Command :", cmd); - MOVE_SERVO(Z_PROBE_SERVO_NR, cmd); + servo[Z_PROBE_SERVO_NR].move(cmd); safe_delay(_MAX(ms, (uint32_t)BLTOUCH_DELAY)); // BLTOUCH_DELAY is also the *minimum* delay return triggered(); } diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index 53d5720cce9b..f5664bc59855 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -29,7 +29,6 @@ #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; diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index 474933aa1946..285a86ca63f5 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -52,6 +52,7 @@ #define HAS_SIDE_BY_SIDE 1 #endif +#define _ROT ((MAX7219_ROTATE + 360) % 360) #if _ROT == 0 || _ROT == 180 #define MAX7219_X_LEDS TERN(HAS_SIDE_BY_SIDE, 8, MAX7219_LINES) #define MAX7219_Y_LEDS TERN(HAS_SIDE_BY_SIDE, MAX7219_LINES, 8) @@ -62,6 +63,15 @@ #error "MAX7219_ROTATE must be a multiple of +/- 90°." #endif +#ifdef MAX7219_DEBUG_PROFILE + CodeProfiler::Mode CodeProfiler::mode = ACCUMULATE_AVERAGE; + uint8_t CodeProfiler::instance_count = 0; + uint32_t CodeProfiler::last_calc_time = micros(); + uint8_t CodeProfiler::time_fraction = 0; + uint32_t CodeProfiler::total_time = 0; + uint16_t CodeProfiler::call_count = 0; +#endif + Max7219 max7219; uint8_t Max7219::led_line[MAX7219_LINES]; // = { 0 }; @@ -69,7 +79,7 @@ uint8_t Max7219::suspended; // = 0; #define LINE_REG(Q) (max7219_reg_digit0 + ((Q) & 0x7)) -#if _ROT == 0 || _ROT == 270 +#if (_ROT == 0 || _ROT == 270) == DISABLED(MAX7219_REVERSE_EACH) #define _LED_BIT(Q) (7 - ((Q) & 0x7)) #else #define _LED_BIT(Q) ((Q) & 0x7) @@ -266,26 +276,27 @@ void Max7219::set(const uint8_t line, const uint8_t bits) { #endif // MAX7219_NUMERIC // Modify a single LED bit and send the changed line -void Max7219::led_set(const uint8_t x, const uint8_t y, const bool on) { +void Max7219::led_set(const uint8_t x, const uint8_t y, const bool on, uint8_t * const rcm/*=nullptr*/) { if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_set"), x, y); if (BIT_7219(x, y) == on) return; XOR_7219(x, y); refresh_unit_line(LED_IND(x, y)); + if (rcm != nullptr) *rcm |= _BV(LED_IND(x, y) & 0x07); } -void Max7219::led_on(const uint8_t x, const uint8_t y) { +void Max7219::led_on(const uint8_t x, const uint8_t y, uint8_t * const rcm/*=nullptr*/) { if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_on"), x, y); - led_set(x, y, true); + led_set(x, y, true, rcm); } -void Max7219::led_off(const uint8_t x, const uint8_t y) { +void Max7219::led_off(const uint8_t x, const uint8_t y, uint8_t * const rcm/*=nullptr*/) { if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_off"), x, y); - led_set(x, y, false); + led_set(x, y, false, rcm); } -void Max7219::led_toggle(const uint8_t x, const uint8_t y) { +void Max7219::led_toggle(const uint8_t x, const uint8_t y, uint8_t * const rcm/*=nullptr*/) { if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_toggle"), x, y); - led_set(x, y, !BIT_7219(x, y)); + led_set(x, y, !BIT_7219(x, y), rcm); } void Max7219::send_row(const uint8_t row) { @@ -448,7 +459,7 @@ void Max7219::register_setup() { pulse_load(); // Tell the chips to load the clocked out data } -#ifdef MAX7219_INIT_TEST +#if MAX7219_INIT_TEST uint8_t test_mode = 0; millis_t next_patt_ms; @@ -536,13 +547,9 @@ void Max7219::init() { register_setup(); - LOOP_LE_N(i, 7) { // Empty registers to turn all LEDs off - led_line[i] = 0x00; - send(max7219_reg_digit0 + i, 0); - pulse_load(); // Tell the chips to load the clocked out data - } + clear(); - #ifdef MAX7219_INIT_TEST + #if MAX7219_INIT_TEST start_test_pattern(); #endif } @@ -554,41 +561,55 @@ void Max7219::init() { */ // Apply changes to update a marker -void Max7219::mark16(const uint8_t pos, const uint8_t v1, const uint8_t v2) { +void Max7219::mark16(const uint8_t pos, const uint8_t v1, const uint8_t v2, uint8_t * const rcm/*=nullptr*/) { #if MAX7219_X_LEDS > 8 // At least 16 LEDs on the X-Axis. Use single line. - led_off(v1 & 0xF, pos); - led_on(v2 & 0xF, pos); + led_off(v1 & 0xF, pos, rcm); + led_on(v2 & 0xF, pos, rcm); #elif MAX7219_Y_LEDS > 8 // At least 16 LEDs on the Y-Axis. Use a single column. - led_off(pos, v1 & 0xF); - led_on(pos, v2 & 0xF); + led_off(pos, v1 & 0xF, rcm); + led_on(pos, v2 & 0xF, rcm); #else // Single 8x8 LED matrix. Use two lines to get 16 LEDs. - led_off(v1 & 0x7, pos + (v1 >= 8)); - led_on(v2 & 0x7, pos + (v2 >= 8)); + led_off(v1 & 0x7, pos + (v1 >= 8), rcm); + led_on(v2 & 0x7, pos + (v2 >= 8), rcm); #endif } // Apply changes to update a tail-to-head range -void Max7219::range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, const uint8_t nh) { +void Max7219::range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, + const uint8_t nh, uint8_t * const rcm/*=nullptr*/) { #if MAX7219_X_LEDS > 8 // At least 16 LEDs on the X-Axis. Use single line. if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF) - led_off(n & 0xF, y); + led_off(n & 0xF, y, rcm); if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF) - led_on(n & 0xF, y); + led_on(n & 0xF, y, rcm); #elif MAX7219_Y_LEDS > 8 // At least 16 LEDs on the Y-Axis. Use a single column. if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF) - led_off(y, n & 0xF); + led_off(y, n & 0xF, rcm); if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF) - led_on(y, n & 0xF); + led_on(y, n & 0xF, rcm); #else // Single 8x8 LED matrix. Use two lines to get 16 LEDs. if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF) - led_off(n & 0x7, y + (n >= 8)); + led_off(n & 0x7, y + (n >= 8), rcm); if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF) - led_on(n & 0x7, y + (n >= 8)); + led_on(n & 0x7, y + (n >= 8), rcm); #endif } // Apply changes to update a quantity -void Max7219::quantity16(const uint8_t pos, const uint8_t ov, const uint8_t nv) { +void Max7219::quantity(const uint8_t pos, const uint8_t ov, const uint8_t nv, uint8_t * const rcm/*=nullptr*/) { + for (uint8_t i = _MIN(nv, ov); i < _MAX(nv, ov); i++) + led_set( + #if MAX7219_X_LEDS >= MAX7219_Y_LEDS + i, pos // Single matrix or multiple matrices in Landscape + #else + pos, i // Multiple matrices in Portrait + #endif + , nv >= ov + , rcm + ); +} + +void Max7219::quantity16(const uint8_t pos, const uint8_t ov, const uint8_t nv, uint8_t * const rcm/*=nullptr*/) { for (uint8_t i = _MIN(nv, ov); i < _MAX(nv, ov); i++) led_set( #if MAX7219_X_LEDS > 8 // At least 16 LEDs on the X-Axis. Use single line. @@ -599,6 +620,7 @@ void Max7219::quantity16(const uint8_t pos, const uint8_t ov, const uint8_t nv) i >> 1, pos + (i & 1) #endif , nv >= ov + , rcm ); } @@ -636,16 +658,20 @@ void Max7219::idle_tasks() { register_setup(); } - #ifdef MAX7219_INIT_TEST + #if MAX7219_INIT_TEST if (test_mode) { run_test_pattern(); return; } #endif + // suspend updates and record which lines have changed for batching later + suspended++; + uint8_t row_change_mask = 0x00; + #if ENABLED(MAX7219_DEBUG_PRINTER_ALIVE) if (do_blink) { - led_toggle(MAX7219_X_LEDS - 1, MAX7219_Y_LEDS - 1); + led_toggle(MAX7219_X_LEDS - 1, MAX7219_Y_LEDS - 1, &row_change_mask); next_blink = ms + 1000; } #endif @@ -655,7 +681,7 @@ void Max7219::idle_tasks() { static int16_t last_head_cnt = 0xF, last_tail_cnt = 0xF; if (last_head_cnt != head || last_tail_cnt != tail) { - range16(MAX7219_DEBUG_PLANNER_HEAD, last_tail_cnt, tail, last_head_cnt, head); + range16(MAX7219_DEBUG_PLANNER_HEAD, last_tail_cnt, tail, last_head_cnt, head, &row_change_mask); last_head_cnt = head; last_tail_cnt = tail; } @@ -665,7 +691,7 @@ void Max7219::idle_tasks() { #ifdef MAX7219_DEBUG_PLANNER_HEAD static int16_t last_head_cnt = 0x1; if (last_head_cnt != head) { - mark16(MAX7219_DEBUG_PLANNER_HEAD, last_head_cnt, head); + mark16(MAX7219_DEBUG_PLANNER_HEAD, last_head_cnt, head, &row_change_mask); last_head_cnt = head; } #endif @@ -673,7 +699,7 @@ void Max7219::idle_tasks() { #ifdef MAX7219_DEBUG_PLANNER_TAIL static int16_t last_tail_cnt = 0x1; if (last_tail_cnt != tail) { - mark16(MAX7219_DEBUG_PLANNER_TAIL, last_tail_cnt, tail); + mark16(MAX7219_DEBUG_PLANNER_TAIL, last_tail_cnt, tail, &row_change_mask); last_tail_cnt = tail; } #endif @@ -684,11 +710,26 @@ void Max7219::idle_tasks() { static int16_t last_depth = 0; const int16_t current_depth = (head - tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1) & 0xF; if (current_depth != last_depth) { - quantity16(MAX7219_DEBUG_PLANNER_QUEUE, last_depth, current_depth); + quantity16(MAX7219_DEBUG_PLANNER_QUEUE, last_depth, current_depth, &row_change_mask); last_depth = current_depth; } #endif + #ifdef MAX7219_DEBUG_PROFILE + static uint8_t last_time_fraction = 0; + const uint8_t current_time_fraction = (uint16_t(CodeProfiler::get_time_fraction()) * MAX7219_NUMBER_UNITS + 8) / 16; + if (current_time_fraction != last_time_fraction) { + quantity(MAX7219_DEBUG_PROFILE, last_time_fraction, current_time_fraction, &row_change_mask); + last_time_fraction = current_time_fraction; + } + #endif + + // batch line updates + suspended--; + if (!suspended) + LOOP_L_N(i, 8) if (row_change_mask & _BV(i)) + refresh_line(i); + // After resume() automatically do a refresh() if (suspended == 0x80) { suspended = 0; diff --git a/Marlin/src/feature/max7219.h b/Marlin/src/feature/max7219.h index 809bda6d4b35..a6b110fdf4c9 100644 --- a/Marlin/src/feature/max7219.h +++ b/Marlin/src/feature/max7219.h @@ -47,7 +47,6 @@ #ifndef MAX7219_ROTATE #define MAX7219_ROTATE 0 #endif -#define _ROT ((MAX7219_ROTATE + 360) % 360) #ifndef MAX7219_NUMBER_UNITS #define MAX7219_NUMBER_UNITS 1 @@ -73,6 +72,67 @@ #define max7219_reg_shutdown 0x0C #define max7219_reg_displayTest 0x0F +#ifdef MAX7219_DEBUG_PROFILE + // This class sums up the amount of time for which its instances exist. + // By default there is one instantiated for the duration of the idle() + // function. But an instance can be created in any code block to measure + // the time spent from the point of instantiation until the CPU leaves + // block. Be careful about having multiple instances of CodeProfiler as + // it does not guard against double counting. In general mixing ISR and + // non-ISR use will require critical sections but note that mode setting + // is atomic so the total or average times can safely be read if you set + // mode to FREEZE first. + class CodeProfiler { + public: + enum Mode : uint8_t { ACCUMULATE_AVERAGE, ACCUMULATE_TOTAL, FREEZE }; + + private: + static Mode mode; + static uint8_t instance_count; + static uint32_t last_calc_time; + static uint32_t total_time; + static uint8_t time_fraction; + static uint16_t call_count; + + uint32_t start_time; + + public: + CodeProfiler() : start_time(micros()) { instance_count++; } + ~CodeProfiler() { + instance_count--; + if (mode == FREEZE) return; + + call_count++; + + const uint32_t now = micros(); + total_time += now - start_time; + + if (mode == ACCUMULATE_TOTAL) return; + + // update time_fraction every hundred milliseconds + if (instance_count == 0 && ELAPSED(now, last_calc_time + 100000)) { + time_fraction = total_time * 128 / (now - last_calc_time); + last_calc_time = now; + total_time = 0; + } + } + + static void set_mode(Mode _mode) { mode = _mode; } + static void reset() { + time_fraction = 0; + last_calc_time = micros(); + total_time = 0; + call_count = 0; + } + // returns fraction of total time which was measured, scaled from 0 to 128 + static uint8_t get_time_fraction() { return time_fraction; } + // returns total time in microseconds + static uint32_t get_total_time() { return total_time; } + + static uint16_t get_call_count() { return call_count; } + }; +#endif + class Max7219 { public: static uint8_t led_line[MAX7219_LINES]; @@ -110,10 +170,10 @@ class Max7219 { #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); - static void led_off(const uint8_t x, const uint8_t y); - static void led_toggle(const uint8_t x, const uint8_t y); + static void led_set(const uint8_t x, const uint8_t y, const bool on, uint8_t * const rcm=nullptr); + static void led_on(const uint8_t x, const uint8_t y, uint8_t * const rcm=nullptr); + static void led_off(const uint8_t x, const uint8_t y, uint8_t * const rcm=nullptr); + static void led_toggle(const uint8_t x, const uint8_t y, uint8_t * const rcm=nullptr); // Set all LEDs in a single column static void set_column(const uint8_t col, const uint32_t val); @@ -147,11 +207,12 @@ class Max7219 { static void set(const uint8_t line, const uint8_t bits); static void send_row(const uint8_t row); static void send_column(const uint8_t col); - static void mark16(const uint8_t y, const uint8_t v1, const uint8_t v2); - static void range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, const uint8_t nh); - static void quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv); + static void mark16(const uint8_t y, const uint8_t v1, const uint8_t v2, uint8_t * const rcm=nullptr); + static void range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, const uint8_t nh, uint8_t * const rcm=nullptr); + static void quantity(const uint8_t y, const uint8_t ov, const uint8_t nv, uint8_t * const rcm=nullptr); + static void quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv, uint8_t * const rcm=nullptr); - #ifdef MAX7219_INIT_TEST + #if MAX7219_INIT_TEST static void test_pattern(); static void run_test_pattern(); static void start_test_pattern(); diff --git a/Marlin/src/feature/meatpack.cpp b/Marlin/src/feature/meatpack.cpp index b2899243b2fb..07ff41e5be22 100644 --- a/Marlin/src/feature/meatpack.cpp +++ b/Marlin/src/feature/meatpack.cpp @@ -26,7 +26,7 @@ * Algorithm & Implementation: Scott Mudge - mail@scottmudge.com * Date: Dec. 2020 * - * Character Frequencies from ~30 MB of comment-stripped gcode: + * Character Frequencies from ~30 MB of comment-stripped G-code: * '1' -> 4451136 '4' -> 1353273 '\n' -> 1087683 '-' -> 90242 * '0' -> 4253577 '9' -> 1352147 'G' -> 1075806 'Z' -> 34109 * ' ' -> 3053297 '3' -> 1262929 'X' -> 975742 'M' -> 11879 diff --git a/Marlin/src/feature/meatpack.h b/Marlin/src/feature/meatpack.h index a56e65b6cc30..98a535e5923f 100644 --- a/Marlin/src/feature/meatpack.h +++ b/Marlin/src/feature/meatpack.h @@ -29,7 +29,7 @@ * 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 + * analysis on a wide variety of 3D printing G-code samples, and found ~93% of all G-code 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 @@ -38,7 +38,7 @@ * * 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. + * out unnecessary comments, the end result is G-code 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 diff --git a/Marlin/src/feature/mmu/mmu2-serial-protocol.md b/Marlin/src/feature/mmu/mmu2-serial-protocol.md index 7ff0901742af..93135e406f36 100644 --- a/Marlin/src/feature/mmu/mmu2-serial-protocol.md +++ b/Marlin/src/feature/mmu/mmu2-serial-protocol.md @@ -51,7 +51,7 @@ 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 +We don't wait for a response here but immediately continue with the next G-code which should be one or more extruder moves to feed the filament into the hotend. diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index a469c988c9cf..a4718b53d9d8 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -939,7 +939,7 @@ bool MMU2::load_filament_to_nozzle(const uint8_t index) { * 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 + * It is not used after T0 .. T4 command (select filament), in such case, G-code is responsible for loading * filament to nozzle. */ void MMU2::load_to_nozzle() { @@ -1031,8 +1031,7 @@ void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { const float es = pgm_read_float(&(step->extrude)); const feedRate_t fr_mm_m = pgm_read_float(&(step->feedRate)); - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("E step ", es, "/", fr_mm_m); + DEBUG_ECHO_MSG("E step ", es, "/", fr_mm_m); current_position.e += es; line_to_current_position(MMM_TO_MMS(fr_mm_m)); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index ac5852f91a1a..e9cb2df594d2 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -711,9 +711,13 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ TERN_(HAS_FILAMENT_SENSOR, runout.reset()); - TERN(DWIN_LCD_PROUI, DWIN_Print_Resume(), ui.reset_status()); - TERN_(HAS_MARLINUI_MENU, ui.return_to_status()); - TERN_(DWIN_LCD_PROUI, HMI_ReturnScreen()); + #if ENABLED(DWIN_LCD_PROUI) + DWIN_Print_Resume(); + HMI_ReturnScreen(); + #else + ui.reset_status(); + ui.return_to_status(); + #endif } #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/feature/power_monitor.cpp b/Marlin/src/feature/power_monitor.cpp index 504f1ea48e3b..5a9db1ec24a1 100644 --- a/Marlin/src/feature/power_monitor.cpp +++ b/Marlin/src/feature/power_monitor.cpp @@ -53,7 +53,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor void PowerMonitor::draw_current() { const float amps = getAmps(); lcd_put_u8str(amps < 100 ? ftostr31ns(amps) : ui16tostr4rj((uint16_t)amps)); - lcd_put_wchar('A'); + lcd_put_lchar('A'); } #endif @@ -61,7 +61,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor void PowerMonitor::draw_voltage() { const float volts = getVolts(); lcd_put_u8str(volts < 100 ? ftostr31ns(volts) : ui16tostr4rj((uint16_t)volts)); - lcd_put_wchar('V'); + lcd_put_lchar('V'); } #endif @@ -69,7 +69,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor void PowerMonitor::draw_power() { const float power = getPower(); lcd_put_u8str(power < 100 ? ftostr31ns(power) : ui16tostr4rj((uint16_t)power)); - lcd_put_wchar('W'); + lcd_put_lchar('W'); } #endif diff --git a/Marlin/src/feature/power_monitor.h b/Marlin/src/feature/power_monitor.h index f6e0b292e30c..fa0690905333 100644 --- a/Marlin/src/feature/power_monitor.h +++ b/Marlin/src/feature/power_monitor.h @@ -32,7 +32,7 @@ struct pm_lpf_t { uint32_t filter_buf; float value; void add_sample(const uint16_t sample) { - filter_buf = filter_buf - (filter_buf >> K_VALUE) + (uint32_t(sample) << K_SCALE); + filter_buf += (uint32_t(sample) << K_SCALE) - (filter_buf >> K_VALUE); } void capture() { value = filter_buf * (SCALE * (1.0f / (1UL << (PM_K_VALUE + PM_K_SCALE)))); diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 52bb471b0f7e..da38646a3674 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -39,17 +39,26 @@ #endif SpindleLaser cutter; -uint8_t SpindleLaser::power; +bool SpindleLaser::enable_state; // Virtual enable state, controls enable pin if present and or apply power if > 0 +uint8_t SpindleLaser::power, // Actual power output 0-255 ocr or "0 = off" > 0 = "on" + SpindleLaser::last_power_applied; // = 0 // Basic power state tracking + #if ENABLED(LASER_FEATURE) - cutter_test_pulse_t SpindleLaser::testPulse = 50; // Test fire Pulse time ms value. + cutter_test_pulse_t SpindleLaser::testPulse = 50; // (ms) Test fire pulse default duration + uint8_t SpindleLaser::last_block_power; // = 0 // Track power changes for dynamic inline power + feedRate_t SpindleLaser::feedrate_mm_m = 1500, + SpindleLaser::last_feedrate_mm_m; // = 0 // (mm/min) Track feedrate changes for dynamic power #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 -#if ENABLED(MARLIN_DEV_MODE) - cutter_frequency_t SpindleLaser::frequency; // PWM frequency setting; range: 2K - 50K -#endif +bool SpindleLaser::isReadyForUI = false; // Ready to apply power setting from the UI to OCR +CutterMode SpindleLaser::cutter_mode = CUTTER_MODE_STANDARD; // Default is standard mode + +constexpr cutter_cpower_t SpindleLaser::power_floor; +cutter_power_t SpindleLaser::menuPower = 0, // Power value via LCD menu in PWM, PERCENT, or RPM based on configured format set by CUTTER_POWER_UNIT. + SpindleLaser::unitPower = 0; // Unit power is in PWM, PERCENT, or RPM based on CUTTER_POWER_UNIT. + +cutter_frequency_t SpindleLaser::frequency; // PWM frequency setting; range: 2K - 50K + #define SPINDLE_LASER_PWM_OFF TERN(SPINDLE_LASER_PWM_INVERT, 255, 0) /** @@ -57,21 +66,21 @@ cutter_power_t SpindleLaser::menuPower, // Power s */ void SpindleLaser::init() { #if ENABLED(SPINDLE_SERVO) - MOVE_SERVO(SPINDLE_SERVO_NR, SPINDLE_SERVO_MIN); + servo[SPINDLE_SERVO_NR].move(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); // Init rotation to clockwise (M3) #endif + #if ENABLED(HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY + frequency = SPINDLE_LASER_FREQUENCY; + hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); + #endif #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed #endif - #if ENABLED(HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY - hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); - TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); - #endif #if ENABLED(AIR_EVACUATION) OUT_WRITE(AIR_EVACUATION_PIN, !AIR_EVACUATION_ACTIVE); // Init Vacuum/Blower OFF #endif @@ -89,7 +98,7 @@ void SpindleLaser::init() { */ void SpindleLaser::_set_ocr(const uint8_t ocr) { #if ENABLED(HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY - hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); + hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); #endif hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } @@ -106,36 +115,41 @@ void SpindleLaser::init() { #endif // SPINDLE_LASER_USE_PWM /** - * Apply power for laser/spindle + * Apply power for Laser or Spindle * * Apply cutter power value for PWM, Servo, and on/off pin. * - * @param opwr Power value. Range 0 to MAX. When 0 disable spindle/laser. + * @param opwr Power value. Range 0 to MAX. */ void SpindleLaser::apply_power(const uint8_t opwr) { - static uint8_t last_power_applied = 0; - if (opwr == last_power_applied) return; - last_power_applied = opwr; - power = opwr; - #if ENABLED(SPINDLE_LASER_USE_PWM) - if (cutter.unitPower == 0 && CUTTER_UNIT_IS(RPM)) { - ocr_off(); - isReady = false; - } - else if (ENABLED(CUTTER_POWER_RELATIVE) || enabled()) { - set_ocr(power); - isReady = true; - } - else { - 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; - #endif + if (enabled() || opwr == 0) { // 0 check allows us to disable where no ENA pin exists + // Test and set the last power used to improve performance + if (opwr == last_power_applied) return; + last_power_applied = opwr; + // Handle PWM driven or just simple on/off + #if ENABLED(SPINDLE_LASER_USE_PWM) + if (CUTTER_UNIT_IS(RPM) && unitPower == 0) + ocr_off(); + else if (ENABLED(CUTTER_POWER_RELATIVE) || enabled() || opwr == 0) { + set_ocr(opwr); + isReadyForUI = true; + } + else + ocr_off(); + #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); + isReadyForUI = true; + #endif + } + else { + #if PIN_EXISTS(SPINDLE_LASER_ENA) + WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); + #endif + isReadyForUI = false; // Only used for UI display updates. + TERN_(SPINDLE_LASER_USE_PWM, ocr_off()); + } } #if ENABLED(SPINDLE_CHANGE_DIR) @@ -159,8 +173,8 @@ void SpindleLaser::apply_power(const uint8_t opwr) { #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_enable() { WRITE(AIR_ASSIST_PIN, AIR_ASSIST_ACTIVE); } // Turn ON + void SpindleLaser::air_assist_disable() { WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_ACTIVE); } // Turn OFF void SpindleLaser::air_assist_toggle() { TOGGLE(AIR_ASSIST_PIN); } // Toggle state #endif diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index e948d2d37b73..b945032d8ea2 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -30,90 +30,102 @@ #include "spindle_laser_types.h" -#if USE_BEEPER +#if HAS_BEEPER #include "../libs/buzzer.h" #endif -#if ENABLED(LASER_POWER_INLINE) - #include "../module/planner.h" -#endif +// Inline laser power +#include "../module/planner.h" #define PCT_TO_PWM(X) ((X) * 255 / 100) #define PCT_TO_SERVO(X) ((X) * 180 / 100) -// #define _MAP(N,S1,S2,D1,D2) ((N)*_MAX((D2)-(D1),0)/_MAX((S2)-(S1),1)+(D1)) + +// Laser/Cutter operation mode +enum CutterMode : int8_t { + CUTTER_MODE_ERROR = -1, + CUTTER_MODE_STANDARD, // M3 power is applied directly and waits for planner moves to sync. + CUTTER_MODE_CONTINUOUS, // M3 or G1/2/3 move power is controlled within planner blocks, set with 'M3 I', cleared with 'M5 I'. + CUTTER_MODE_DYNAMIC // M4 laser power is proportional to the feed rate, set with 'M4 I', cleared with 'M5 I'. +}; class SpindleLaser { public: - static const inline uint8_t pct_to_ocr(const_float_t pct) { return uint8_t(PCT_TO_PWM(pct)); } + static CutterMode cutter_mode; - // cpower = configured values (e.g., SPEED_POWER_MAX) + static constexpr uint8_t pct_to_ocr(const_float_t pct) { return uint8_t(PCT_TO_PWM(pct)); } + // cpower = configured values (e.g., SPEED_POWER_MAX) // 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; + static constexpr cutter_cpower_t power_floor = TERN(CUTTER_POWER_RELATIVE, SPEED_POWER_MIN, 0); + static constexpr uint8_t cpwr_to_pct(const cutter_cpower_t cpwr) { + return cpwr ? round(100.0f * (cpwr - power_floor) / (SPEED_POWER_MAX - power_floor)) : 0; } - // 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 = ( + // Convert config defines from RPM to %, angle or PWM when in Spindle mode + // and convert from PERCENT to PWM when in Laser mode + static constexpr cutter_power_t cpwr_to_upwr(const cutter_cpower_t cpwr) { // STARTUP power to Unit power + return ( #if ENABLED(SPINDLE_FEATURE) - // Spindle configured values are in RPM + // Spindle configured define values are in RPM #if CUTTER_UNIT_IS(RPM) - 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)) + cpwr // to same + #elif CUTTER_UNIT_IS(PERCENT) + cpwr_to_pct(cpwr) // to Percent + #elif CUTTER_UNIT_IS(SERVO) + PCT_TO_SERVO(cpwr_to_pct(cpwr)) // to SERVO angle + #else + PCT_TO_PWM(cpwr_to_pct(cpwr)) // to PWM #endif #else - // Laser configured values are in PCT + // Laser configured define values are in Percent #if CUTTER_UNIT_IS(PWM255) - PCT_TO_PWM(cpwr) + PCT_TO_PWM(cpwr) // to PWM #else - cpwr // to RPM/PCT + cpwr // to same #endif #endif ); - return upwr; } - 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); } + static constexpr cutter_power_t mpower_min() { return cpwr_to_upwr(SPEED_POWER_MIN); } + static constexpr 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 + static cutter_test_pulse_t testPulse; // (ms) Test fire pulse duration + static uint8_t last_block_power; // Track power changes for dynamic power + + static feedRate_t feedrate_mm_m, last_feedrate_mm_m; // (mm/min) Track feedrate changes for dynamic power + static bool laser_feedrate_changed() { + const bool changed = last_feedrate_mm_m != feedrate_mm_m; + if (changed) last_feedrate_mm_m = feedrate_mm_m; + return changed; + } #endif - static bool isReady; // Ready to apply power setting from the UI to OCR - static uint8_t power; + static bool isReadyForUI; // Ready to apply power setting from the UI to OCR + static bool enable_state; + static uint8_t power, + last_power_applied; // Basic power state tracking - #if ENABLED(MARLIN_DEV_MODE) - static cutter_frequency_t frequency; // Set PWM frequency; range: 2K-50K - #endif + static cutter_frequency_t frequency; // Set PWM frequency; range: 2K-50K static cutter_power_t menuPower, // Power as set via LCD menu in PWM, Percentage or RPM unitPower; // Power as displayed status in PWM, Percentage or RPM static void init(); - #if ENABLED(MARLIN_DEV_MODE) + #if ENABLED(HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY static void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } #endif // Modifying this function should update everywhere static bool enabled(const cutter_power_t opwr) { return opwr > 0; } - static bool enabled() { return enabled(power); } + static bool enabled() { return enable_state; } static void apply_power(const uint8_t inpow); FORCE_INLINE static void refresh() { apply_power(power); } - FORCE_INLINE static void set_power(const uint8_t upwr) { power = upwr; refresh(); } #if ENABLED(SPINDLE_LASER_USE_PWM) @@ -124,7 +136,6 @@ class SpindleLaser { public: static void set_ocr(const uint8_t ocr); - static void ocr_set_power(const uint8_t ocr) { power = ocr; set_ocr(ocr); } static void ocr_off(); /** @@ -142,78 +153,76 @@ class SpindleLaser { ); } - /** - * Correct power to configured range - */ - static cutter_power_t power_to_range(const cutter_power_t pwr) { - return power_to_range(pwr, _CUTTER_POWER(CUTTER_POWER_UNIT)); - } - - static cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit) { - static constexpr float - min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, round(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)), - max_pct = TERN(SPINDLE_FEATURE, 100, SPEED_POWER_MAX); - if (pwr <= 0) return 0; - cutter_power_t upwr; - switch (pwrUnit) { - case _CUTTER_POWER_PWM255: - upwr = cutter_power_t( - (pwr < pct_to_ocr(min_pct)) ? pct_to_ocr(min_pct) // Use minimum if set below - : (pwr > pct_to_ocr(max_pct)) ? pct_to_ocr(max_pct) // Use maximum if set above - : pwr - ); - break; - case _CUTTER_POWER_PERCENT: - upwr = cutter_power_t( - (pwr < min_pct) ? min_pct // Use minimum if set below - : (pwr > max_pct) ? max_pct // Use maximum if set above - : pwr // PCT - ); - break; - case _CUTTER_POWER_RPM: - upwr = cutter_power_t( - (pwr < SPEED_POWER_MIN) ? SPEED_POWER_MIN // Use minimum if set below - : (pwr > SPEED_POWER_MAX) ? SPEED_POWER_MAX // Use maximum if set above - : pwr // Calculate OCR value - ); - break; - default: break; - } - return upwr; - } - #endif // SPINDLE_LASER_USE_PWM /** - * Enable/Disable spindle/laser - * @param enable true = enable; false = disable + * Correct power to configured range */ - static void set_enabled(const bool enable) { - uint8_t value = 0; - if (enable) { - #if ENABLED(SPINDLE_LASER_USE_PWM) - if (power) - value = power; - else if (unitPower) - value = upower_to_ocr(cpwr_to_upwr(SPEED_POWER_STARTUP)); - #else - value = 255; - #endif + static cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit=_CUTTER_POWER(CUTTER_POWER_UNIT)) { + static constexpr float + min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, round(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)), + max_pct = TERN(SPINDLE_FEATURE, 100, SPEED_POWER_MAX); + if (pwr <= 0) return 0; + cutter_power_t upwr; + switch (pwrUnit) { + case _CUTTER_POWER_PWM255: { // PWM + const uint8_t pmin = pct_to_ocr(min_pct), pmax = pct_to_ocr(max_pct); + upwr = cutter_power_t(constrain(pwr, pmin, pmax)); + } break; + case _CUTTER_POWER_PERCENT: // Percent + upwr = cutter_power_t(constrain(pwr, min_pct, max_pct)); + break; + case _CUTTER_POWER_RPM: // Calculate OCR value + upwr = cutter_power_t(constrain(pwr, SPEED_POWER_MIN, SPEED_POWER_MAX)); + break; + default: break; } - set_power(value); + return upwr; } - static void disable() { isReady = false; set_enabled(false); } - /** - * Wait for spindle to spin up or spin down + * Enable Laser or Spindle output. + * It's important to prevent changing the power output value during inline cutter operation. + * Inline power is adjusted in the planner to support LASER_TRAP_POWER and CUTTER_MODE_DYNAMIC mode. + * + * This method accepts one of the following control states: + * + * - For CUTTER_MODE_STANDARD the cutter power is either full on/off or ocr-based and it will apply + * SPEED_POWER_STARTUP if no value is assigned. * - * @param on true = state to on; false = state to off. + * - For CUTTER_MODE_CONTINUOUS inline and power remains where last set and the cutter output enable flag is set. + * + * - CUTTER_MODE_DYNAMIC is also inline-based and it just sets the enable output flag. + * + * - For CUTTER_MODE_ERROR set the output enable_state flag directly and set power to 0 for any mode. + * This mode allows a global power shutdown action to occur. */ - static void power_delay(const bool on) { - #if DISABLED(LASER_POWER_INLINE) - safe_delay(on ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY); + static void set_enabled(const bool enable) { + switch (cutter_mode) { + case CUTTER_MODE_STANDARD: + apply_power(enable ? TERN(SPINDLE_LASER_USE_PWM, (power ?: (unitPower ? upower_to_ocr(cpwr_to_upwr(SPEED_POWER_STARTUP)) : 0)), 255) : 0); + break; + case CUTTER_MODE_CONTINUOUS: + TERN_(LASER_FEATURE, set_inline_enabled(enable)); + break; + case CUTTER_MODE_DYNAMIC: + TERN_(LASER_FEATURE, set_inline_enabled(enable)); + break; + case CUTTER_MODE_ERROR: // Error mode, no enable and kill power. + enable_state = false; + apply_power(0); + } + #if SPINDLE_LASER_ENA_PIN + WRITE(SPINDLE_LASER_ENA_PIN, enable ? SPINDLE_LASER_ACTIVE_STATE : !SPINDLE_LASER_ACTIVE_STATE); #endif + enable_state = enable; + } + + static void disable() { isReadyForUI = false; set_enabled(false); } + + // Wait for spindle/laser to startup or shutdown + static void power_delay(const bool on) { + safe_delay(on ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY); } #if ENABLED(SPINDLE_CHANGE_DIR) @@ -225,122 +234,97 @@ class SpindleLaser { #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 bool air_evac_state() { // Get current state + 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 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 bool air_assist_state() { // Get current state + 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 bool air_assist_state() { // Get current state return (READ(AIR_ASSIST_PIN) == AIR_ASSIST_ACTIVE); } #endif #if HAS_MARLINUI_MENU - static void enable_with_dir(const bool reverse) { - isReady = true; - const uint8_t ocr = TERN(SPINDLE_LASER_USE_PWM, upower_to_ocr(menuPower), 255); - if (menuPower) - power = ocr; - else - menuPower = cpwr_to_upwr(SPEED_POWER_STARTUP); - unitPower = menuPower; - 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_FEATURE) + static void enable_with_dir(const bool reverse) { + isReadyForUI = true; + const uint8_t ocr = TERN(SPINDLE_LASER_USE_PWM, upower_to_ocr(menuPower), 255); + if (menuPower) + power = ocr; + else + menuPower = cpwr_to_upwr(SPEED_POWER_STARTUP); + unitPower = menuPower; + 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()); } + #endif // SPINDLE_FEATURE #if ENABLED(SPINDLE_LASER_USE_PWM) static void update_from_mpower() { - if (isReady) power = upower_to_ocr(menuPower); + if (isReadyForUI) power = upower_to_ocr(menuPower); unitPower = menuPower; } #endif #if ENABLED(LASER_FEATURE) + // Toggle the laser on/off with menuPower. Apply SPEED_POWER_STARTUP if it was 0 on entry. + static void laser_menu_toggle(const bool state) { + set_enabled(state); + if (state) { + if (!menuPower) menuPower = cpwr_to_upwr(SPEED_POWER_STARTUP); + power = upower_to_ocr(menuPower); + apply_power(power); + } + } + /** * 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 void test_fire_pulse() { - TERN_(USE_BEEPER, buzzer.tone(30, 3000)); - enable_forward(); // Turn Laser on (Spindle speak but same funct) + TERN_(HAS_BEEPER, buzzer.tone(30, 3000)); + cutter_mode = CUTTER_MODE_STANDARD;// Menu needs standard mode. + laser_menu_toggle(true); // Laser On delay(testPulse); // Delay for time set by user in pulse ms menu screen. - disable(); // Turn laser off + laser_menu_toggle(false); // Laser Off } - #endif + #endif // LASER_FEATURE #endif // HAS_MARLINUI_MENU - #if ENABLED(LASER_POWER_INLINE) - /** - * Inline power adds extra fields to the planner block - * to handle laser power and scale to movement speed. - */ + #if ENABLED(LASER_FEATURE) - // Force disengage planner power control - static void inline_disable() { - isReady = false; - unitPower = 0; - planner.laser_inline.status.isPlanned = false; - planner.laser_inline.status.isEnabled = false; - planner.laser_inline.power = 0; + // Dynamic mode rate calculation + static uint8_t calc_dynamic_power() { + if (feedrate_mm_m > 65535) return 255; // Too fast, go always on + uint16_t rate = uint16_t(feedrate_mm_m); // 16 bits from the G-code parser float input + rate >>= 8; // Take the G-code input e.g. F40000 and shift off the lower bits to get an OCR value from 1-255 + return uint8_t(rate); } // Inline modes of all other functions; all enable planner inline power control - static void set_inline_enabled(const bool enable) { - if (enable) - inline_power(255); - else { - isReady = false; - unitPower = menuPower = 0; - planner.laser_inline.status.isPlanned = false; - TERN(SPINDLE_LASER_USE_PWM, inline_ocr_power, inline_power)(0); - } - } + static void set_inline_enabled(const bool enable) { planner.laser_inline.status.isEnabled = enable;} // Set the power for subsequent movement blocks - static void inline_power(const cutter_power_t upwr) { - unitPower = menuPower = upwr; - #if ENABLED(SPINDLE_LASER_USE_PWM) - #if ENABLED(SPEED_POWER_RELATIVE) && !CUTTER_UNIT_IS(RPM) // relative mode does not turn laser off at 0, except for RPM - planner.laser_inline.status.isEnabled = true; - planner.laser_inline.power = upower_to_ocr(upwr); - isReady = true; - #else - inline_ocr_power(upower_to_ocr(upwr)); - #endif - #else - planner.laser_inline.status.isEnabled = enabled(upwr); - planner.laser_inline.power = upwr; - isReady = enabled(upwr); - #endif + static void inline_power(const cutter_power_t cpwr) { + TERN(SPINDLE_LASER_USE_PWM, power = planner.laser_inline.power = cpwr, planner.laser_inline.power = cpwr > 0 ? 255 : 0); } - static void inline_direction(const bool) { /* never */ } - - #if ENABLED(SPINDLE_LASER_USE_PWM) - static void inline_ocr_power(const uint8_t ocrpwr) { - isReady = ocrpwr > 0; - planner.laser_inline.status.isEnabled = ocrpwr > 0; - planner.laser_inline.power = ocrpwr; - } - #endif - #endif // LASER_POWER_INLINE + #endif // LASER_FEATURE - static void kill() { - TERN_(LASER_POWER_INLINE, inline_disable()); - disable(); - } + static void kill() { disable(); } }; extern SpindleLaser cutter; diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h index d249a20e7531..2f36a68a1a32 100644 --- a/Marlin/src/feature/spindle_laser_types.h +++ b/Marlin/src/feature/spindle_laser_types.h @@ -74,12 +74,10 @@ typedef IF<(SPEED_POWER_MAX > 255), uint16_t, uint8_t>::type cutter_cpower_t; #endif #endif +typedef uint16_t cutter_frequency_t; + #if ENABLED(LASER_FEATURE) typedef uint16_t cutter_test_pulse_t; #define CUTTER_MENU_PULSE_TYPE uint16_3 -#endif - -#if ENABLED(MARLIN_DEV_MODE) - typedef uint16_t cutter_frequency_t; #define CUTTER_MENU_FREQUENCY_TYPE uint16_5 #endif diff --git a/Marlin/src/feature/z_stepper_align.cpp b/Marlin/src/feature/z_stepper_align.cpp index fdbd464ea1b4..9dba21d8219d 100644 --- a/Marlin/src/feature/z_stepper_align.cpp +++ b/Marlin/src/feature/z_stepper_align.cpp @@ -33,35 +33,35 @@ ZStepperAlign z_stepper_align; -xy_pos_t ZStepperAlign::xy[NUM_Z_STEPPER_DRIVERS]; +xy_pos_t ZStepperAlign::xy[NUM_Z_STEPPERS]; #if HAS_Z_STEPPER_ALIGN_STEPPER_XY - xy_pos_t ZStepperAlign::stepper_xy[NUM_Z_STEPPER_DRIVERS]; + xy_pos_t ZStepperAlign::stepper_xy[NUM_Z_STEPPERS]; #endif void ZStepperAlign::reset_to_default() { #ifdef Z_STEPPER_ALIGN_XY constexpr xy_pos_t xy_init[] = Z_STEPPER_ALIGN_XY; - static_assert(COUNT(xy_init) == NUM_Z_STEPPER_DRIVERS, + static_assert(COUNT(xy_init) == NUM_Z_STEPPERS, "Z_STEPPER_ALIGN_XY requires " - #if NUM_Z_STEPPER_DRIVERS == 4 + #if NUM_Z_STEPPERS == 4 "four {X,Y} entries (Z, Z2, Z3, and Z4)." - #elif NUM_Z_STEPPER_DRIVERS == 3 + #elif NUM_Z_STEPPERS == 3 "three {X,Y} entries (Z, Z2, and Z3)." #else "two {X,Y} entries (Z and Z2)." #endif ); - #define VALIDATE_ALIGN_POINT(N) static_assert(N >= NUM_Z_STEPPER_DRIVERS || Probe::build_time::can_reach(xy_init[N]), \ + #define VALIDATE_ALIGN_POINT(N) static_assert(N >= NUM_Z_STEPPERS || 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 // !Z_STEPPER_ALIGN_XY const xy_pos_t xy_init[] = { - #if NUM_Z_STEPPER_DRIVERS >= 3 // First probe point... + #if NUM_Z_STEPPERS >= 3 // First probe point... #if !Z_STEPPERS_ORIENTATION { probe.min_x(), probe.min_y() }, // SW #elif Z_STEPPERS_ORIENTATION == 1 @@ -73,7 +73,7 @@ void ZStepperAlign::reset_to_default() { #else #error "Z_STEPPERS_ORIENTATION must be from 0 to 3 (first point SW, NW, NE, SE)." #endif - #if NUM_Z_STEPPER_DRIVERS == 4 // 3 more points... + #if NUM_Z_STEPPERS == 4 // 3 more points... #if !Z_STEPPERS_ORIENTATION { probe.min_x(), probe.max_y() }, { probe.max_x(), probe.max_y() }, { probe.max_x(), probe.min_y() } // SW #elif Z_STEPPERS_ORIENTATION == 1 @@ -106,11 +106,11 @@ void ZStepperAlign::reset_to_default() { #if HAS_Z_STEPPER_ALIGN_STEPPER_XY constexpr xy_pos_t stepper_xy_init[] = Z_STEPPER_ALIGN_STEPPER_XY; static_assert( - COUNT(stepper_xy_init) == NUM_Z_STEPPER_DRIVERS, + COUNT(stepper_xy_init) == NUM_Z_STEPPERS, "Z_STEPPER_ALIGN_STEPPER_XY requires " - #if NUM_Z_STEPPER_DRIVERS == 4 + #if NUM_Z_STEPPERS == 4 "four {X,Y} entries (Z, Z2, Z3, and Z4)." - #elif NUM_Z_STEPPER_DRIVERS == 3 + #elif NUM_Z_STEPPERS == 3 "three {X,Y} entries (Z, Z2, and Z3)." #endif ); diff --git a/Marlin/src/feature/z_stepper_align.h b/Marlin/src/feature/z_stepper_align.h index 8a12cd18b0bd..f3f9abb845b9 100644 --- a/Marlin/src/feature/z_stepper_align.h +++ b/Marlin/src/feature/z_stepper_align.h @@ -29,10 +29,10 @@ class ZStepperAlign { public: - static xy_pos_t xy[NUM_Z_STEPPER_DRIVERS]; + static xy_pos_t xy[NUM_Z_STEPPERS]; #if HAS_Z_STEPPER_ALIGN_STEPPER_XY - static xy_pos_t stepper_xy[NUM_Z_STEPPER_DRIVERS]; + static xy_pos_t stepper_xy[NUM_Z_STEPPERS]; #endif static void reset_to_default(); diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 6691d6c9ab55..21fa08fc107a 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -293,10 +293,10 @@ typedef struct { 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.x = bedlevel.get_mesh_x(p1.x) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx; + e.x = bedlevel.get_mesh_x(p2.x) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx; + s.y = bedlevel.get_mesh_y(p1.y) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dy; + e.y = bedlevel.get_mesh_y(p2.y) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dy; s.z = e.z = layer_height; #if HAS_ENDSTOPS @@ -448,7 +448,7 @@ typedef struct { 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) }; + const xy_pos_t m = { bedlevel.get_mesh_x(i), bedlevel.get_mesh_y(j) }; // Get the distance to this intersection float f = (pos - m).magnitude(); @@ -729,7 +729,7 @@ void GcodeSuite::G26() { if (location.valid()) { TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location.pos, ExtUI::G26_POINT_START)); - const xy_pos_t circle = _GET_MESH_POS(location.pos); + const xy_pos_t circle = { bedlevel.get_mesh_x(location.pos.a), bedlevel.get_mesh_y(location.pos.b) }; // If this mesh location is outside the printable radius, skip it. if (!position_is_reachable(circle)) continue; @@ -738,8 +738,8 @@ void GcodeSuite::G26() { // which is always drawn counter-clockwise. const xy_int8_t st = location; const bool f = st.y == 0, - r = st.x >= GRID_MAX_POINTS_X - 1, - b = st.y >= GRID_MAX_POINTS_Y - 1; + r = st.x >= (GRID_MAX_POINTS_X) - 1, + b = st.y >= (GRID_MAX_POINTS_Y) - 1; #if ENABLED(ARC_SUPPORT) diff --git a/Marlin/src/gcode/bedlevel/G42.cpp b/Marlin/src/gcode/bedlevel/G42.cpp index a2896ed6c705..cb5ed9740604 100644 --- a/Marlin/src/gcode/bedlevel/G42.cpp +++ b/Marlin/src/gcode/bedlevel/G42.cpp @@ -48,8 +48,8 @@ void GcodeSuite::G42() { // Move to current_position, as modified by I, J, P parameters destination = current_position; - if (hasI) destination.x = _GET_MESH_X(ix); - if (hasJ) destination.y = _GET_MESH_Y(iy); + if (hasI) destination.x = bedlevel.get_mesh_x(ix); + if (hasJ) destination.y = bedlevel.get_mesh_y(iy); #if HAS_PROBE_XY_OFFSET if (parser.boolval('P')) { diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index c8325b1fc5c1..277f95b9ffe1 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -71,13 +71,13 @@ void GcodeSuite::M420() { start.set(x_min, y_min); spacing.set((x_max - x_min) / (GRID_MAX_CELLS_X), (y_max - y_min) / (GRID_MAX_CELLS_Y)); - bbl.set_grid(spacing, start); + bedlevel.set_grid(spacing, start); #endif GRID_LOOP(x, y) { - Z_VALUES(x, y) = 0.001 * random(-200, 200); - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y))); + bedlevel.z_values[x][y] = 0.001 * random(-200, 200); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y])); } - TERN_(AUTO_BED_LEVELING_BILINEAR, bbl.refresh_bed_level()); + TERN_(AUTO_BED_LEVELING_BILINEAR, bedlevel.refresh_bed_level()); SERIAL_ECHOPGM("Simulated " STRINGIFY(GRID_MAX_POINTS_X) "x" STRINGIFY(GRID_MAX_POINTS_Y) " mesh "); SERIAL_ECHOPGM(" (", x_min); SERIAL_CHAR(','); SERIAL_ECHO(y_min); @@ -101,7 +101,7 @@ void GcodeSuite::M420() { set_bed_leveling_enabled(false); #if ENABLED(EEPROM_SETTINGS) - const int8_t storage_slot = parser.has_value() ? parser.value_int() : ubl.storage_slot; + const int8_t storage_slot = parser.has_value() ? parser.value_int() : bedlevel.storage_slot; const int16_t a = settings.calc_num_meshes(); if (!a) { @@ -116,7 +116,7 @@ void GcodeSuite::M420() { } settings.load_mesh(storage_slot); - ubl.storage_slot = storage_slot; + bedlevel.storage_slot = storage_slot; #else @@ -128,10 +128,10 @@ void GcodeSuite::M420() { // L or V display the map info if (parser.seen("LV")) { - ubl.display_map(parser.byteval('T')); + bedlevel.display_map(parser.byteval('T')); SERIAL_ECHOPGM("Mesh is "); - if (!ubl.mesh_is_valid()) SERIAL_ECHOPGM("in"); - SERIAL_ECHOLNPGM("valid\nStorage slot: ", ubl.storage_slot); + if (!bedlevel.mesh_is_valid()) SERIAL_ECHOPGM("in"); + SERIAL_ECHOLNPGM("valid\nStorage slot: ", bedlevel.storage_slot); } #endif // AUTO_BED_LEVELING_UBL @@ -148,7 +148,7 @@ void GcodeSuite::M420() { #if ENABLED(AUTO_BED_LEVELING_UBL) set_bed_leveling_enabled(false); - ubl.adjust_mesh_to_mean(true, cval); + bedlevel.adjust_mesh_to_mean(true, cval); #else @@ -156,7 +156,7 @@ void GcodeSuite::M420() { // Get the sum and average of all mesh values float mesh_sum = 0; - GRID_LOOP(x, y) mesh_sum += Z_VALUES(x, y); + GRID_LOOP(x, y) mesh_sum += bedlevel.z_values[x][y]; const float zmean = mesh_sum / float(GRID_MAX_POINTS); #else // midrange @@ -164,7 +164,7 @@ void GcodeSuite::M420() { // 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); + const float z = bedlevel.z_values[x][y]; NOMORE(lo_val, z); NOLESS(hi_val, z); } @@ -178,10 +178,10 @@ void GcodeSuite::M420() { set_bed_leveling_enabled(false); // Subtract the mean from all values GRID_LOOP(x, y) { - Z_VALUES(x, y) -= zmean; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y))); + bedlevel.z_values[x][y] -= zmean; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y])); } - TERN_(AUTO_BED_LEVELING_BILINEAR, bbl.refresh_bed_level()); + TERN_(AUTO_BED_LEVELING_BILINEAR, bedlevel.refresh_bed_level()); } #endif @@ -202,10 +202,10 @@ void GcodeSuite::M420() { #else if (leveling_is_valid()) { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - bbl.print_leveling_grid(); + bedlevel.print_leveling_grid(); #elif ENABLED(MESH_BED_LEVELING) SERIAL_ECHOLNPGM("Mesh Bed Level data:"); - mbl.report_mesh(); + bedlevel.report_mesh(); #endif } #endif diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 3743f1ffc6a9..a2c53b5ab253 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -74,14 +74,18 @@ #endif #endif +static void pre_g29_return(const bool retry, const bool did) { + if (!retry) { + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE, false)); + } + if (did) { + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_LevelingDone()); + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); + } +} + #define G29_RETURN(retry, did) do{ \ - if (TERN(G29_RETRY_AND_RECOVER, !retry, true)) { \ - TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE, false)); \ - } \ - if (did) { \ - TERN_(HAS_DWIN_E3V2_BASIC, DWIN_LevelingDone()); \ - TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); \ - } \ + pre_g29_return(TERN0(G29_RETRY_AND_RECOVER, retry), did); \ return TERN_(G29_RETRY_AND_RECOVER, retry); \ }while(0) @@ -313,8 +317,8 @@ G29_TYPE GcodeSuite::G29() { if (!isnan(rx) && !isnan(ry)) { // Get nearest i / j from rx / ry - i = (rx - bbl.get_grid_start().x) / bbl.get_grid_spacing().x + 0.5f; - j = (ry - bbl.get_grid_start().y) / bbl.get_grid_spacing().y + 0.5f; + i = (rx - bedlevel.grid_start.x) / bedlevel.grid_spacing.x + 0.5f; + j = (ry - bedlevel.grid_start.y) / bedlevel.grid_spacing.y + 0.5f; LIMIT(i, 0, (GRID_MAX_POINTS_X) - 1); LIMIT(j, 0, (GRID_MAX_POINTS_Y) - 1); } @@ -323,11 +327,13 @@ G29_TYPE GcodeSuite::G29() { if (WITHIN(i, 0, (GRID_MAX_POINTS_X) - 1) && WITHIN(j, 0, (GRID_MAX_POINTS_Y) - 1)) { set_bed_leveling_enabled(false); - Z_VALUES_ARR[i][j] = rz; - bbl.refresh_bed_level(); + bedlevel.z_values[i][j] = rz; + bedlevel.refresh_bed_level(); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, rz)); - set_bed_leveling_enabled(abl.reenable); - if (abl.reenable) report_current_position(); + if (abl.reenable) { + set_bed_leveling_enabled(true); + report_current_position(); + } } G29_RETURN(false, false); } // parser.seen_test('W') @@ -428,7 +434,7 @@ G29_TYPE GcodeSuite::G29() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> 3-point Leveling"); points[0].z = points[1].z = points[2].z = 0; // Probe at 3 arbitrary points #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_LevelingStart()); + TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart()); #endif TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); @@ -499,7 +505,7 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) if (!abl.dryrun - && (abl.gridSpacing != bbl.get_grid_spacing() || abl.probe_position_lf != bbl.get_grid_start()) + && (abl.gridSpacing != bedlevel.grid_spacing || abl.probe_position_lf != bedlevel.grid_start) ) { // Reset grid to 0.0 or "not probed". (Also disables ABL) reset_bed_level(); @@ -507,6 +513,10 @@ G29_TYPE GcodeSuite::G29() { // Can't re-enable (on error) until the new grid is written abl.reenable = false; } + + // Pre-populate local Z values from the stored mesh + TERN_(IS_KINEMATIC, COPY(abl.z_values, bedlevel.z_values)); + #endif // AUTO_BED_LEVELING_BILINEAR } // !g29_in_progress @@ -725,7 +735,7 @@ G29_TYPE GcodeSuite::G29() { #endif - abl.reenable = false; + abl.reenable = false; // Don't re-enable after modifying the mesh idle_no_sleep(); } // inner @@ -792,14 +802,14 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) if (abl.dryrun) - bbl.print_leveling_grid(&abl.z_values); + bedlevel.print_leveling_grid(&abl.z_values); else { - bbl.set_grid(abl.gridSpacing, abl.probe_position_lf); - COPY(Z_VALUES_ARR, abl.z_values); - TERN_(IS_KINEMATIC, bbl.extrapolate_unprobed_bed_level()); - bbl.refresh_bed_level(); + bedlevel.set_grid(abl.gridSpacing, abl.probe_position_lf); + COPY(bedlevel.z_values, abl.z_values); + TERN_(IS_KINEMATIC, bedlevel.extrapolate_unprobed_bed_level()); + bedlevel.refresh_bed_level(); - bbl.print_leveling_grid(); + bedlevel.print_leveling_grid(); } #elif ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -910,33 +920,28 @@ G29_TYPE GcodeSuite::G29() { current_position = converted; if (DEBUGGING(LEVELING)) DEBUG_POS("G29 corrected XYZ", current_position); - } - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + abl.reenable = true; + } - if (!abl.dryrun) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("G29 uncorrected Z:", current_position.z); + // Auto Bed Leveling is complete! Enable if possible. + if (abl.reenable) { + planner.leveling_active = true; + sync_plan_position(); + } - // Unapply the offset because it is going to be immediately applied - // and cause compensation movement in Z - const float fade_scaling_factor = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.fade_scaling_factor_for_z(current_position.z), 1); - current_position.z -= fade_scaling_factor * bbl.get_z_correction(current_position); + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(" corrected Z:", current_position.z); - } + // Auto Bed Leveling is complete! Enable if possible. + if (!abl.dryrun || abl.reenable) set_bed_leveling_enabled(true); - #endif // ABL_PLANAR + #endif - // Auto Bed Leveling is complete! Enable if possible. - planner.leveling_active = !abl.dryrun || abl.reenable; } // !isnan(abl.measured_z) // Restore state after probing if (!faux) restore_feedrate_and_scaling(); - // Sync the planner from the current_position - if (planner.leveling_active) sync_plan_position(); - TERN_(HAS_BED_PROBE, probe.move_z_after_probing()); #ifdef Z_PROBE_END_SCRIPT diff --git a/Marlin/src/gcode/bedlevel/abl/M421.cpp b/Marlin/src/gcode/bedlevel/abl/M421.cpp index 0c12268cb109..3272ea1bd227 100644 --- a/Marlin/src/gcode/bedlevel/abl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/abl/M421.cpp @@ -58,11 +58,11 @@ void GcodeSuite::M421() { sy = iy >= 0 ? iy : 0, ey = iy >= 0 ? iy : GRID_MAX_POINTS_Y - 1; LOOP_S_LE_N(x, sx, ex) { LOOP_S_LE_N(y, sy, ey) { - Z_VALUES_ARR[x][y] = zval + (hasQ ? Z_VALUES_ARR[x][y] : 0); - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES_ARR[x][y])); + bedlevel.z_values[x][y] = zval + (hasQ ? bedlevel.z_values[x][y] : 0); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y])); } } - bbl.refresh_bed_level(); + bedlevel.refresh_bed_level(); } else SERIAL_ERROR_MSG(STR_ERR_MESH_XY); diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index e04073b122c9..b9440f78b2e9 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -93,14 +93,14 @@ void GcodeSuite::G29() { SERIAL_ECHOPGM("Mesh Bed Leveling "); if (leveling_is_valid()) { serialprintln_onoff(planner.leveling_active); - mbl.report_mesh(); + bedlevel.report_mesh(); } else SERIAL_ECHOLNPGM("has no data."); break; case MeshStart: - mbl.reset(); + bedlevel.reset(); mbl_probe_index = 0; if (!ui.wait_for_move) { queue.inject(parser.seen_test('N') ? F("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : F("G29S2")); @@ -165,7 +165,7 @@ void GcodeSuite::G29() { } else { // Save Z for the previous mesh position - mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z); + bedlevel.set_zigzag_z(mbl_probe_index - 1, current_position.z); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, current_position.z)); TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(_MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS), current_position.z)); SET_SOFT_ENDSTOP_LOOSE(false); @@ -175,8 +175,8 @@ void GcodeSuite::G29() { // 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); - mbl.zigzag(mbl_probe_index++, ix, iy); - _manual_goto_xy({ mbl.index_to_xpos[ix], mbl.index_to_ypos[iy] }); + bedlevel.zigzag(mbl_probe_index++, ix, iy); + _manual_goto_xy({ bedlevel.index_to_xpos[ix], bedlevel.index_to_ypos[iy] }); } else { // Move to the after probing position @@ -232,9 +232,9 @@ void GcodeSuite::G29() { return echo_not_entered('J'); if (parser.seenval('Z')) { - mbl.z_values[ix][iy] = parser.value_linear_units(); - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, mbl.z_values[ix][iy])); - TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ix, iy, mbl.z_values[ix][iy])); + bedlevel.z_values[ix][iy] = parser.value_linear_units(); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, bedlevel.z_values[ix][iy])); + TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ix, iy, bedlevel.z_values[ix][iy])); } else return echo_not_entered('Z'); @@ -242,7 +242,7 @@ void GcodeSuite::G29() { case MeshSetZOffset: if (parser.seenval('Z')) - mbl.z_offset = parser.value_linear_units(); + bedlevel.z_offset = parser.value_linear_units(); else return echo_not_entered('Z'); break; diff --git a/Marlin/src/gcode/bedlevel/mbl/M421.cpp b/Marlin/src/gcode/bedlevel/mbl/M421.cpp index 1368ab0bef98..e23683d55f34 100644 --- a/Marlin/src/gcode/bedlevel/mbl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/M421.cpp @@ -43,9 +43,9 @@ */ void GcodeSuite::M421() { const bool hasX = parser.seen('X'), hasI = parser.seen('I'); - const int8_t ix = hasI ? parser.value_int() : hasX ? mbl.probe_index_x(RAW_X_POSITION(parser.value_linear_units())) : -1; + const int8_t ix = hasI ? parser.value_int() : hasX ? bedlevel.probe_index_x(RAW_X_POSITION(parser.value_linear_units())) : -1; const bool hasY = parser.seen('Y'), hasJ = parser.seen('J'); - const int8_t iy = hasJ ? parser.value_int() : hasY ? mbl.probe_index_y(RAW_Y_POSITION(parser.value_linear_units())) : -1; + const int8_t iy = hasJ ? parser.value_int() : hasY ? bedlevel.probe_index_y(RAW_Y_POSITION(parser.value_linear_units())) : -1; const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); if (int(hasI && hasJ) + int(hasX && hasY) != 1 || !(hasZ || hasQ)) @@ -53,7 +53,7 @@ void GcodeSuite::M421() { else if (ix < 0 || iy < 0) SERIAL_ERROR_MSG(STR_ERR_MESH_XY); else - mbl.set_z(ix, iy, parser.value_linear_units() + (hasQ ? mbl.z_values[ix][iy] : 0)); + bedlevel.set_z(ix, iy, parser.value_linear_units() + (hasQ ? bedlevel.z_values[ix][iy] : 0)); } #endif // MESH_BED_LEVELING diff --git a/Marlin/src/gcode/bedlevel/ubl/G29.cpp b/Marlin/src/gcode/bedlevel/ubl/G29.cpp index 932503d72b97..90deab3d2e3e 100644 --- a/Marlin/src/gcode/bedlevel/ubl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/G29.cpp @@ -39,7 +39,7 @@ void GcodeSuite::G29() { TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); - ubl.G29(); + bedlevel.G29(); TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); } diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index c11a20ebf33c..ff74f4c6f744 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -56,7 +56,7 @@ void GcodeSuite::M421() { hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); - if (hasC) ij = ubl.find_closest_mesh_point_of_type(CLOSEST, current_position); + if (hasC) ij = bedlevel.find_closest_mesh_point_of_type(CLOSEST, current_position); // Test for bad parameter combinations if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ || hasN)) @@ -66,7 +66,7 @@ void GcodeSuite::M421() { else if (!WITHIN(ij.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(ij.y, 0, GRID_MAX_POINTS_Y - 1)) SERIAL_ERROR_MSG(STR_ERR_MESH_XY); else { - float &zval = ubl.z_values[ij.x][ij.y]; // Altering this Mesh Point + float &zval = bedlevel.z_values[ij.x][ij.y]; // Altering this Mesh Point zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ij.x, ij.y, zval)); diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 2a1fec84aef2..384fc7210c42 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -59,7 +59,7 @@ #include "../../libs/L64XX/L64XX_Marlin.h" #endif -#if ENABLED(LASER_MOVE_G28_OFF) +#if ENABLED(LASER_FEATURE) #include "../../feature/spindle_laser.h" #endif @@ -169,7 +169,7 @@ motion_state.jerk_state = planner.max_jerk; planner.max_jerk.set(0, 0 OPTARG(DELTA, 0)); #endif - planner.reset_acceleration_rates(); + planner.refresh_acceleration_rates(); return motion_state; } @@ -178,7 +178,7 @@ 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(); + planner.refresh_acceleration_rates(); } #endif // IMPROVE_HOMING_RELIABILITY @@ -205,7 +205,12 @@ void GcodeSuite::G28() { DEBUG_SECTION(log_G28, "G28", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); - TERN_(LASER_MOVE_G28_OFF, cutter.set_inline_enabled(false)); // turn off laser + /* + * Set the laser power to false to stop the planner from processing the current power setting. + */ + #if ENABLED(LASER_FEATURE) + planner.laser_inline.status.isPowered = false; + #endif #if ENABLED(DUAL_X_CARRIAGE) bool IDEX_saved_duplication_state = extruder_duplication_enabled; @@ -321,6 +326,9 @@ void GcodeSuite::G28() { stepperW.rms_current(W_CURRENT_HOME); if (DEBUGGING(LEVELING)) debug_current(F(STR_W), tmc_save_current_W, W_CURRENT_HOME); #endif + #if SENSORLESS_STALLGUARD_DELAY + safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle + #endif #endif #if ENABLED(IMPROVE_HOMING_RELIABILITY) @@ -576,6 +584,9 @@ void GcodeSuite::G28() { #if HAS_CURRENT_HOME(W) stepperW.rms_current(tmc_save_current_W); #endif + #if SENSORLESS_STALLGUARD_DELAY + safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle + #endif #endif // HAS_HOMING_CURRENT ui.refresh(); diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 7f487abd6b87..ffe53b63fbef 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -71,9 +71,9 @@ float lcd_probe_pt(const xy_pos_t &xy); void ac_home() { endstops.enable(true); - TERN_(HAS_DELTA_SENSORLESS_PROBING, probe.set_homing_current(true)); + TERN_(SENSORLESS_HOMING, endstops.set_homing_current(true)); home_delta(); - TERN_(HAS_DELTA_SENSORLESS_PROBING, probe.set_homing_current(false)); + TERN_(SENSORLESS_HOMING, endstops.set_homing_current(false)); endstops.not_homing(); } @@ -390,6 +390,8 @@ static float auto_tune_a(const float dcr) { * X Don't activate stallguard on X. * Y Don't activate stallguard on Y. * Z Don't activate stallguard on Z. + * + * S Save offset_sensorless_adj */ void GcodeSuite::G33() { @@ -411,7 +413,8 @@ void GcodeSuite::G33() { dcr -= probe_at_offset ? _MAX(total_offset, PROBING_MARGIN) : total_offset; #endif NOMORE(dcr, DELTA_PRINTABLE_RADIUS); - if (parser.seenval('R')) dcr -= _MAX(parser.value_float(),0); + if (parser.seenval('R')) dcr -= _MAX(parser.value_float(), 0.0f); + TERN_(HAS_DELTA_SENSORLESS_PROBING, dcr *= sensorless_radius_factor); const float calibration_precision = parser.floatval('C', 0.0f); if (calibration_precision < 0) { @@ -434,9 +437,8 @@ void GcodeSuite::G33() { const bool stow_after_each = parser.seen_test('E'); #if HAS_DELTA_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')); + probe.test_sensitivity = { !parser.seen_test('X'), !parser.seen_test('Y'), !parser.seen_test('Z') }; + const bool do_save_offset_adj = parser.seen_test('S'); #endif const bool _0p_calibration = probe_points == 0, @@ -475,6 +477,25 @@ void GcodeSuite::G33() { if (!_0p_calibration) ac_home(); + #if HAS_DELTA_SENSORLESS_PROBING + if (verbose_level > 0 && do_save_offset_adj) { + offset_sensorless_adj.reset(); + + auto caltower = [&](Probe::sense_bool_t s){ + float z_at_pt[NPP + 1]; + LOOP_CAL_ALL(rad) z_at_pt[rad] = 0.0f; + probe.test_sensitivity = s; + if (probe_calibration_points(z_at_pt, 1, dcr, false, false, probe_at_offset)) + probe.set_offset_sensorless_adj(z_at_pt[CEN]); + }; + caltower({ true, false, false }); // A + caltower({ false, true, false }); // B + caltower({ false, false, true }); // C + + probe.test_sensitivity = { true, true, true }; // reset to all + } + #endif + do { // start iterations float z_at_pt[NPP + 1] = { 0.0f }; @@ -598,8 +619,17 @@ void GcodeSuite::G33() { // print report - if (verbose_level == 3 || verbose_level == 0) + if (verbose_level == 3 || verbose_level == 0) { print_calibration_results(z_at_pt, _tower_results, _opposite_results); + #if HAS_DELTA_SENSORLESS_PROBING + if (verbose_level == 0 && probe_points == 1) { + if (do_save_offset_adj) + probe.set_offset_sensorless_adj(z_at_pt[CEN]); + else + probe.refresh_largest_sensorless_adj(); + } + #endif + } if (verbose_level != 0) { // !dry run if ((zero_std_dev >= test_precision && iterations > force_iterations) || zero_std_dev <= calibration_precision) { // end iterations @@ -660,6 +690,9 @@ void GcodeSuite::G33() { ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index)); TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); + #if HAS_DELTA_SENSORLESS_PROBING + probe.test_sensitivity = { true, true, true }; + #endif } #endif // DELTA_AUTO_CALIBRATION diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 38fa9266b430..6fdebb69b0f0 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -91,7 +91,7 @@ void GcodeSuite::G34() { digipot_i2c.set_current(Z_AXIS, target_current) #elif HAS_TRINAMIC_CONFIG const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT); - static uint16_t previous_current_arr[NUM_Z_STEPPER_DRIVERS]; + static uint16_t previous_current_arr[NUM_Z_STEPPERS]; #if AXIS_IS_TMC(Z) previous_current_arr[0] = stepperZ.getMilliamps(); stepperZ.rms_current(target_current); diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index d1f82e7e9874..d68207885d39 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -52,9 +52,9 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" -#if NUM_Z_STEPPER_DRIVERS >= 3 +#if NUM_Z_STEPPERS >= 3 #define TRIPLE_Z 1 - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 #define QUAD_Z 1 #endif #endif @@ -180,11 +180,11 @@ void GcodeSuite::G34() { // This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration. #if !HAS_Z_STEPPER_ALIGN_STEPPER_XY - float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N_1(NUM_Z_STEPPER_DRIVERS, 10000.0f); + float last_z_align_move[NUM_Z_STEPPERS] = ARRAY_N_1(NUM_Z_STEPPERS, 10000.0f); #else float last_z_align_level_indicator = 10000.0f; #endif - float z_measured[NUM_Z_STEPPER_DRIVERS] = { 0 }, + float z_measured[NUM_Z_STEPPERS] = { 0 }, z_maxdiff = 0.0f, amplification = z_auto_align_amplification; @@ -217,9 +217,9 @@ void GcodeSuite::G34() { float z_measured_max = -100000.0f; // Probe all positions (one per Z-Stepper) - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + LOOP_L_N(i, NUM_Z_STEPPERS) { // iteration odd/even --> downward / upward stepper sequence - const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPER_DRIVERS - 1 - i : i; + const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPERS - 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); @@ -270,20 +270,20 @@ void GcodeSuite::G34() { // This allows the actual adjustment logic to be shared by both algorithms. linear_fit_data lfd; incremental_LSF_reset(&lfd); - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + LOOP_L_N(i, NUM_Z_STEPPERS) { SERIAL_ECHOLNPGM("PROBEPT_", i, ": ", z_measured[i]); incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); } finish_incremental_LSF(&lfd); z_measured_min = 100000.0f; - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + LOOP_L_N(i, NUM_Z_STEPPERS) { 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_ECHOLNPGM( - LIST_N(DOUBLE(NUM_Z_STEPPER_DRIVERS), + LIST_N(DOUBLE(NUM_Z_STEPPERS), "Calculated Z1=", z_measured[0], " Z2=", z_measured[1], " Z3=", z_measured[2], @@ -307,7 +307,7 @@ void GcodeSuite::G34() { #if HAS_STATUS_MESSAGE char fstr1[10]; - char msg[6 + (6 + 5) * NUM_Z_STEPPER_DRIVERS + 1] + char msg[6 + (6 + 5) * NUM_Z_STEPPERS + 1] #if TRIPLE_Z , fstr2[10], fstr3[10] #if QUAD_Z @@ -345,12 +345,12 @@ void GcodeSuite::G34() { // 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; + LOOP_L_N(zstepper, NUM_Z_STEPPERS) z_measured_mean += z_measured[zstepper]; + z_measured_mean /= NUM_Z_STEPPERS; // Calculate the sum of the absolute deviations from the mean value float z_align_level_indicator = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) + LOOP_L_N(zstepper, NUM_Z_STEPPERS) z_align_level_indicator += ABS(z_measured[zstepper] - z_measured_mean); // If it's getting worse, stop and throw an error @@ -365,7 +365,7 @@ void GcodeSuite::G34() { bool success_break = true; // Correct the individual stepper offsets - LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) { + LOOP_L_N(zstepper, NUM_Z_STEPPERS) { // Calculate current stepper move float z_align_move = z_measured[zstepper] - z_measured_min; const float z_align_abs = ABS(z_align_move); @@ -515,9 +515,9 @@ void GcodeSuite::M422() { #endif } - if (!WITHIN(position_index, 1, NUM_Z_STEPPER_DRIVERS)) { + if (!WITHIN(position_index, 1, NUM_Z_STEPPERS)) { SERIAL_ECHOF(err_string); - SERIAL_ECHOLNPGM(" index invalid (1.." STRINGIFY(NUM_Z_STEPPER_DRIVERS) ")."); + SERIAL_ECHOLNPGM(" index invalid (1.." STRINGIFY(NUM_Z_STEPPERS) ")."); return; } @@ -544,7 +544,7 @@ void GcodeSuite::M422() { void GcodeSuite::M422_report(const bool forReplay/*=true*/) { report_heading(forReplay, F(STR_Z_AUTO_ALIGN)); - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + LOOP_L_N(i, NUM_Z_STEPPERS) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M422 S"), i + 1, @@ -553,7 +553,7 @@ void GcodeSuite::M422_report(const bool forReplay/*=true*/) { ); } #if HAS_Z_STEPPER_ALIGN_STEPPER_XY - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + LOOP_L_N(i, NUM_Z_STEPPERS) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M422 W"), i + 1, diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 450a71511748..a22608f5b42b 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -438,26 +438,26 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #endif #if HAS_U_AXIS #if ENABLED(CALIBRATION_MEASURE_UMIN) - SERIAL_ECHOLNPAIR(" " STR_U_MIN ": ", m.obj_side[UMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_U_MIN ": ", m.obj_side[UMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_UMAX) - SERIAL_ECHOLNPAIR(" " STR_U_MAX ": ", m.obj_side[UMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_U_MAX ": ", m.obj_side[UMAXIMUM]); #endif #endif #if HAS_V_AXIS #if ENABLED(CALIBRATION_MEASURE_VMIN) - SERIAL_ECHOLNPAIR(" " STR_V_MIN ": ", m.obj_side[VMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_V_MIN ": ", m.obj_side[VMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_VMAX) - SERIAL_ECHOLNPAIR(" " STR_V_MAX ": ", m.obj_side[VMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_V_MAX ": ", m.obj_side[VMAXIMUM]); #endif #endif #if HAS_W_AXIS #if ENABLED(CALIBRATION_MEASURE_WMIN) - SERIAL_ECHOLNPAIR(" " STR_W_MIN ": ", m.obj_side[WMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_W_MIN ": ", m.obj_side[WMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_WMAX) - SERIAL_ECHOLNPAIR(" " STR_W_MAX ": ", m.obj_side[WMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_W_MAX ": ", m.obj_side[WMAXIMUM]); #endif #endif SERIAL_EOL(); diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index ad13b20306ae..c484d4f1b770 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -82,13 +82,13 @@ * - `P` - Run probe temperature calibration. */ -static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); } -static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); } -static void say_successfully_calibrated() { SERIAL_ECHOPGM("Successfully calibrated"); } -static void say_failed_to_calibrate() { SERIAL_ECHOPGM("!Failed to calibrate"); } - #if BOTH(PTC_PROBE, PTC_BED) + 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() { auto report_temps = [](millis_t &ntr, millis_t timeout=0) { idle_no_sleep(); diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 77e0e5c09457..a6c6ff9dae3e 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -47,19 +47,10 @@ void GcodeSuite::M425() { bool noArgs = true; auto axis_can_calibrate = [](const uint8_t a) { + #define _CAN_CASE(N) case N##_AXIS: return AXIS_CAN_CALIBRATE(N); switch (a) { default: return false; - NUM_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), - case U_AXIS: return AXIS_CAN_CALIBRATE(U), - case V_AXIS: return AXIS_CAN_CALIBRATE(V), - case W_AXIS: return AXIS_CAN_CALIBRATE(W) - ); + MAIN_AXIS_MAP(_CAN_CASE) } }; diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index f6ebc670e115..90fad1811c8c 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -93,12 +93,12 @@ #if ENABLED(Z_MULTI_ENDSTOPS) if (parser.seenval('Z')) { const float z_adj = parser.value_linear_units(); - #if NUM_Z_STEPPER_DRIVERS == 2 + #if NUM_Z_STEPPERS == 2 endstops.z2_endstop_adj = z_adj; #else 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) + REPEAT_S(2, INCREMENT(NUM_Z_STEPPERS), _SET_ZADJ) #endif } #endif @@ -114,11 +114,11 @@ SERIAL_ECHOLNPGM_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); #endif #if ENABLED(Z_MULTI_ENDSTOPS) - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 SERIAL_ECHOPGM(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); report_echo_start(forReplay); SERIAL_ECHOPGM(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 report_echo_start(forReplay); SERIAL_ECHOPGM(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); #endif diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 5911f77f2e28..87c1f2ce305e 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -108,12 +108,21 @@ #endif // !NO_VOLUMETRICS /** - * M201: Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000) + * M201: Set max acceleration in units/s^2 for print moves. * - * With multiple extruders use T to specify which one. + * X : Max Acceleration for X + * Y : Max Acceleration for Y + * Z : Max Acceleration for Z + * ... : etc + * E : Max Acceleration for Extruder + * T : Extruder index to set + * + * With XY_FREQUENCY_LIMIT: + * F : Frequency limit for XY...IJKUVW + * S : Speed factor percentage. */ void GcodeSuite::M201() { - if (!parser.seen("T" LOGICAL_AXES_STRING)) + if (!parser.seen("T" STR_AXES_LOGICAL TERN_(XY_FREQUENCY_LIMIT, "FS"))) return M201_report(); const int8_t target_extruder = get_target_extruder_from_command(); @@ -121,7 +130,7 @@ void GcodeSuite::M201() { #ifdef XY_FREQUENCY_LIMIT if (parser.seenval('F')) planner.set_frequency_limit(parser.value_byte()); - if (parser.seenval('G')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100; + if (parser.seenval('S')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100; #endif LOOP_LOGICAL_AXES(i) { @@ -167,7 +176,7 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) { * With multiple extruders use T to specify which one. */ void GcodeSuite::M203() { - if (!parser.seen("T" LOGICAL_AXES_STRING)) + if (!parser.seen("T" STR_AXES_LOGICAL)) return M203_report(); const int8_t target_extruder = get_target_extruder_from_command(); @@ -200,7 +209,7 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) { ); #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(i, E_STEPPERS) { - SERIAL_ECHO_START(); + if (!forReplay) SERIAL_ECHO_START(); SERIAL_ECHOLNPGM_P( PSTR(" M203 T"), i , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]) diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 0fc5edc54e98..688b94c9bf39 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -69,7 +69,7 @@ inline void toggle_pins() { SERIAL_EOL(); } else { - watchdog_refresh(); + hal.watchdog_refresh(); report_pin_state_extended(pin, ignore_protection, true, F("Pulsing ")); #ifdef __STM32F1__ const auto prior_mode = _GET_MODE(i); @@ -98,10 +98,10 @@ inline void toggle_pins() { { pinMode(pin, OUTPUT); for (int16_t j = 0; j < repeat; j++) { - watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait); - watchdog_refresh(); extDigitalWrite(pin, 1); safe_delay(wait); - watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait); - watchdog_refresh(); + hal.watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait); + hal.watchdog_refresh(); extDigitalWrite(pin, 1); safe_delay(wait); + hal.watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait); + hal.watchdog_refresh(); } } #ifdef __STM32F1__ @@ -198,10 +198,10 @@ inline void servo_probe_test() { uint8_t i = 0; SERIAL_ECHOLNPGM(". Deploy & stow 4 times"); do { - MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy + servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy safe_delay(500); deploy_state = READ(PROBE_TEST_PIN); - MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][1]); // Stow + servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow safe_delay(500); stow_state = READ(PROBE_TEST_PIN); } while (++i < 4); @@ -226,7 +226,7 @@ inline void servo_probe_test() { } // Ask the user for a trigger event and measure the pulse width. - MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy + servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy safe_delay(500); SERIAL_ECHOLNPGM("** Please trigger probe within 30 sec **"); uint16_t probe_counter = 0; @@ -256,7 +256,7 @@ inline void servo_probe_test() { } else SERIAL_ECHOLNPGM("FAIL: Noise detected - please re-run test"); - MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][1]); // Stow + servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow return; } } diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 3d1a9cb7cebc..c7610b83a9b9 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -43,7 +43,7 @@ void GcodeSuite::M92() { if (target_extruder < 0) return; // No arguments? Show M92 report. - if (!parser.seen(LOGICAL_AXES_STRING TERN_(MAGIC_NUMBERS_GCODE, "HL"))) + if (!parser.seen(STR_AXES_LOGICAL TERN_(MAGIC_NUMBERS_GCODE, "HL"))) return M92_report(true, target_extruder); LOOP_LOGICAL_AXES(i) { diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index a9beaa3f02cd..c2c8a702a1b6 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -23,6 +23,7 @@ #include "../gcode.h" #include "../../MarlinCore.h" // for stepper_inactive_time, disable_e_steppers #include "../../lcd/marlinui.h" +#include "../../module/motion.h" // for e_axis_mask #include "../../module/stepper.h" #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -43,7 +44,7 @@ inline stepper_flags_t selected_axis_bits() { selected.bits = _BV(INDEX_OF_AXIS(E_AXIS, e)); } else - selected.bits = selected.e_bits(); + selected.bits = e_axis_mask; } #endif selected.bits |= NUM_AXIS_GANG( @@ -210,7 +211,16 @@ void try_to_disable(const stepper_flags_t to_disable) { void GcodeSuite::M18_M84() { if (parser.seenval('S')) { reset_stepper_timeout(); - stepper_inactive_time = parser.value_millis_from_seconds(); + #if HAS_DISABLE_INACTIVE_AXIS + const millis_t ms = parser.value_millis_from_seconds(); + #if LASER_SAFETY_TIMEOUT_MS > 0 + if (ms && ms <= LASER_SAFETY_TIMEOUT_MS) { + SERIAL_ECHO_MSG("M18 timeout must be > ", MS_TO_SEC(LASER_SAFETY_TIMEOUT_MS + 999), " s for laser safety."); + return; + } + #endif + stepper_inactive_time = ms; + #endif } else { if (parser.seen_axis()) { @@ -233,6 +243,6 @@ void GcodeSuite::M18_M84() { else planner.finish_and_disable(); - TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled()); + TERN_(AUTO_BED_LEVELING_UBL, bedlevel.steppers_were_disabled()); } } diff --git a/Marlin/src/gcode/control/M280.cpp b/Marlin/src/gcode/control/M280.cpp index ed156e16e952..82981e44bcee 100644 --- a/Marlin/src/gcode/control/M280.cpp +++ b/Marlin/src/gcode/control/M280.cpp @@ -56,14 +56,14 @@ void GcodeSuite::M280() { while (PENDING(now, end)) { safe_delay(50); now = _MIN(millis(), end); - MOVE_SERVO(servo_index, LROUND(aold + (anew - aold) * (float(now - start) / t))); + servo[servo_index].move(LROUND(aold + (anew - aold) * (float(now - start) / t))); } } #endif // POLARGRAPH - MOVE_SERVO(servo_index, anew); + servo[servo_index].move(anew); } else - DETACH_SERVO(servo_index); + servo[servo_index].detach(); } else SERIAL_ECHO_MSG(" Servo ", servo_index, ": ", servo[servo_index].read()); diff --git a/Marlin/src/gcode/control/M282.cpp b/Marlin/src/gcode/control/M282.cpp index e6f5ce7dccc3..3ac5ac9f5bfc 100644 --- a/Marlin/src/gcode/control/M282.cpp +++ b/Marlin/src/gcode/control/M282.cpp @@ -36,7 +36,7 @@ void GcodeSuite::M282() { const int servo_index = parser.value_int(); if (WITHIN(servo_index, 0, NUM_SERVOS - 1)) - DETACH_SERVO(servo_index); + servo[servo_index].detach(); else SERIAL_ECHO_MSG("Servo ", servo_index, " out of range"); diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index cdb37a1207ad..3c51de6f6f94 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -31,17 +31,27 @@ /** * Laser: * M3 - Laser ON/Power (Ramped power) - * M4 - Laser ON/Power (Continuous power) + * M4 - Laser ON/Power (Ramped power) + * M5 - Set power output to 0 (leaving inline mode unchanged). + * + * M3I - Enable continuous inline power to be processed by the planner, with power + * calculated and set in the planner blocks, processed inline during stepping. + * Within inline mode M3 S-Values will set the power for the next moves e.g. G1 X10 Y10 powers on with the last S-Value. + * M3I must be set before using planner-synced M3 inline S-Values (LASER_POWER_SYNC). + * + * M4I - Set dynamic mode which calculates laser power OCR based on the current feedrate. + * + * M5I - Clear inline mode and set power to 0. * * Spindle: * M3 - Spindle ON (Clockwise) * M4 - Spindle ON (Counter-clockwise) + * M5 - Spindle OFF * * Parameters: - * S - Set power. S0 will turn the spindle/laser off, except in relative mode. - * O - Set power and OCR (oscillator count register) + * S - Set power. S0 will turn the spindle/laser off. * - * If no PWM pin is defined then M3/M4 just turns it on. + * If no PWM pin is defined then M3/M4 just turns it on or off. * * At least 12.8kHz (50Hz * 256) is needed for Spindle PWM. * Hardware PWM is required on AVR. ISRs are too slow. @@ -66,77 +76,81 @@ * PWM duty cycle goes from 0 (off) to 255 (always on). */ void GcodeSuite::M3_M4(const bool is_M4) { - #if EITHER(SPINDLE_LASER_USE_PWM, SPINDLE_SERVO) - auto get_s_power = [] { - if (parser.seenval('S')) { - const float spwr = parser.value_float(); - #if ENABLED(SPINDLE_SERVO) - cutter.unitPower = spwr; - #else - cutter.unitPower = TERN(SPINDLE_LASER_USE_PWM, - cutter.power_to_range(cutter_power_t(round(spwr))), - spwr > 0 ? 255 : 0); - #endif - } - else - cutter.unitPower = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); - return cutter.unitPower; - }; + #if LASER_SAFETY_TIMEOUT_MS > 0 + reset_stepper_timeout(); // Reset timeout to allow subsequent G-code to power the laser (imm.) #endif - #if ENABLED(LASER_POWER_INLINE) - if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) { - // Laser power in inline mode - cutter.inline_direction(is_M4); // Should always be unused - #if ENABLED(SPINDLE_LASER_USE_PWM) - if (parser.seenval('O')) { - cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0); - cutter.inline_ocr_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t) - } - else - cutter.inline_power(cutter.upower_to_ocr(get_s_power())); - #else - cutter.set_inline_enabled(true); - #endif - return; + if (cutter.cutter_mode == CUTTER_MODE_STANDARD) + planner.synchronize(); // Wait for previous movement commands (G0/G1/G2/G3) to complete before changing power + + #if ENABLED(LASER_FEATURE) + if (parser.seen_test('I')) { + cutter.cutter_mode = is_M4 ? CUTTER_MODE_DYNAMIC : CUTTER_MODE_CONTINUOUS; + cutter.inline_power(0); + cutter.set_enabled(true); } - // Non-inline, standard case - cutter.inline_disable(); // Prevent future blocks re-setting the power #endif - planner.synchronize(); // Wait for previous movement commands (G0/G0/G2/G3) to complete before changing power - cutter.set_reverse(is_M4); - - #if ENABLED(SPINDLE_LASER_USE_PWM) - if (parser.seenval('O')) { - cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0); - cutter.ocr_set_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t) + auto get_s_power = [] { + float u; + if (parser.seenval('S')) { + const float v = parser.value_float(); + u = TERN(LASER_POWER_TRAP, v, cutter.power_to_range(v)); } - else - cutter.set_power(cutter.upower_to_ocr(get_s_power())); - #elif ENABLED(SPINDLE_SERVO) - cutter.set_power(get_s_power()); - #else + else if (cutter.cutter_mode == CUTTER_MODE_STANDARD) + u = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); + + cutter.menuPower = cutter.unitPower = u; + + // PWM not implied, power converted to OCR from unit definition and on/off if not PWM. + cutter.power = TERN(SPINDLE_LASER_USE_PWM, cutter.upower_to_ocr(u), u > 0 ? 255 : 0); + return u; + }; + + if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS || cutter.cutter_mode == CUTTER_MODE_DYNAMIC) { // Laser power in inline mode + #if ENABLED(LASER_FEATURE) + planner.laser_inline.status.isPowered = true; // M3 or M4 is powered either way + get_s_power(); // Update cutter.power if seen + #if ENABLED(LASER_POWER_SYNC) + // With power sync we only set power so it does not effect queued inline power sets + planner.buffer_sync_block(BLOCK_BIT_LASER_PWR); // Send the flag, queueing inline power + #else + planner.synchronize(); + cutter.inline_power(cutter.power); + #endif + #endif + } + else { cutter.set_enabled(true); - #endif - cutter.menuPower = cutter.unitPower; + get_s_power(); + cutter.apply_power( + #if ENABLED(SPINDLE_SERVO) + cutter.unitPower + #elif ENABLED(SPINDLE_LASER_USE_PWM) + cutter.upower_to_ocr(cutter.unitPower) + #else + cutter.unitPower > 0 ? 255 : 0 + #endif + ); + TERN_(SPINDLE_CHANGE_DIR, cutter.set_reverse(is_M4)); + } } /** * M5 - Cutter OFF (when moves are complete) */ void GcodeSuite::M5() { - #if ENABLED(LASER_POWER_INLINE) - if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) { - cutter.set_inline_enabled(false); // Laser power in inline mode - return; - } - // Non-inline, standard case - cutter.inline_disable(); // Prevent future blocks re-setting the power - #endif planner.synchronize(); - cutter.set_enabled(false); - cutter.menuPower = cutter.unitPower; + cutter.power = 0; + cutter.apply_power(0); // M5 just kills power, leaving inline mode unchanged + if (cutter.cutter_mode != CUTTER_MODE_STANDARD) { + if (parser.seen_test('I')) { + TERN_(LASER_FEATURE, cutter.inline_power(cutter.power)); + cutter.set_enabled(false); // Needs to happen while we are in inline mode to clear inline power. + cutter.cutter_mode = CUTTER_MODE_STANDARD; // Switch from inline to standard mode. + } + } + cutter.set_enabled(false); // Disable enable output setting } #endif // HAS_CUTTER diff --git a/Marlin/src/gcode/control/M85.cpp b/Marlin/src/gcode/control/M85.cpp index 9c8c02c59aa0..ee868349ed75 100644 --- a/Marlin/src/gcode/control/M85.cpp +++ b/Marlin/src/gcode/control/M85.cpp @@ -29,7 +29,14 @@ void GcodeSuite::M85() { if (parser.seen('S')) { reset_stepper_timeout(); - max_inactive_time = parser.value_millis_from_seconds(); + const millis_t ms = parser.value_millis_from_seconds(); + #if LASER_SAFETY_TIMEOUT_MS > 0 + if (ms && ms <= LASER_SAFETY_TIMEOUT_MS) { + SERIAL_ECHO_MSG("M85 timeout must be > ", MS_TO_SEC(LASER_SAFETY_TIMEOUT_MS + 999), " s for laser safety."); + return; + } + #endif + max_inactive_time = ms; } } diff --git a/Marlin/src/gcode/feature/L6470/M916-M918.cpp b/Marlin/src/gcode/feature/L6470/M916-M918.cpp index 8d614603eda0..9e1f1b98da34 100644 --- a/Marlin/src/gcode/feature/L6470/M916-M918.cpp +++ b/Marlin/src/gcode/feature/L6470/M916-M918.cpp @@ -309,7 +309,6 @@ void GcodeSuite::M917() { } DEBUG_ECHOLNPGM("."); 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/adc/M3426.cpp b/Marlin/src/gcode/feature/adc/M3426.cpp index 8205fa01f2bd..2820c8b88093 100644 --- a/Marlin/src/gcode/feature/adc/M3426.cpp +++ b/Marlin/src/gcode/feature/adc/M3426.cpp @@ -28,6 +28,8 @@ #include "../../../feature/adc/adc_mcp3426.h" +#define MCP3426_BASE_ADDR (0b1101 << 3) + /** * M3426: Read 16 bit (signed) value from I2C MCP3426 ADC device * @@ -36,12 +38,15 @@ * M3426 I 0 or 1, invert reply */ void GcodeSuite::M3426() { - uint8_t channel = parser.byteval('C', 1), // Select the channel 1 or 2 - gain = parser.byteval('G', 1); - const bool inverted = parser.byteval('I') == 1; + uint8_t channel = parser.byteval('C', 1), // Channel 1 or 2 + gain = parser.byteval('G', 1), // Gain 1, 2, 4, or 8 + address = parser.byteval('A', 3); // Address 0-7 (or 104-111) + const bool inverted = parser.boolval('I'); + + if (address <= 7) address += MCP3426_BASE_ADDR; - if (channel <= 2 && (gain == 1 || gain == 2 || gain == 4 || gain == 8)) { - int16_t result = mcp3426.ReadValue(channel, gain); + if (WITHIN(channel, 1, 2) && (gain == 1 || gain == 2 || gain == 4 || gain == 8) && WITHIN(address, MCP3426_BASE_ADDR, MCP3426_BASE_ADDR + 7)) { + int16_t result = mcp3426.ReadValue(channel, gain, address); if (mcp3426.Error == false) { if (inverted) { diff --git a/Marlin/src/gcode/feature/clean/G12.cpp b/Marlin/src/gcode/feature/clean/G12.cpp index 999a9b10bd85..0113170f1d9c 100644 --- a/Marlin/src/gcode/feature/clean/G12.cpp +++ b/Marlin/src/gcode/feature/clean/G12.cpp @@ -45,9 +45,10 @@ * X, Y, Z : Specify axes to move during cleaning. Default: ALL. */ void GcodeSuite::G12() { + // Don't allow nozzle cleaning without homing first - if (homing_needed_error(linear_bits & ~TERN0(NOZZLE_CLEAN_NO_Z, Z_AXIS) & ~TERN0(NOZZLE_CLEAN_NO_Y, Y_AXIS))) - return; + constexpr main_axes_bits_t clean_axis_mask = main_axes_mask & ~TERN0(NOZZLE_CLEAN_NO_Z, Z_AXIS) & ~TERN0(NOZZLE_CLEAN_NO_Y, Y_AXIS); + if (homing_needed_error(clean_axis_mask)) return; #ifdef WIPE_SEQUENCE_COMMANDS if (!parser.seen_any()) { diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index f1f1bcb484cf..9ebe713cde46 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -48,7 +48,7 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_SPI - if (!parser.seen("BS" LOGICAL_AXES_STRING)) + if (!parser.seen("BS" STR_AXES_LOGICAL)) return M907_report(); if (parser.seenval('S')) LOOP_L_N(i, MOTOR_CURRENT_COUNT) stepper.set_digipot_current(i, parser.value_int()); diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index 9e0962fd34f6..b32935b341b9 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -50,14 +50,14 @@ void GcodeSuite::G60() { { const xyze_pos_t &pos = stored_position[slot]; DEBUG_ECHOPGM(STR_SAVED_POS " S", slot, " :"); - DEBUG_ECHOLNPAIR_F_P( + DEBUG_ECHOLNPGM_P( LIST_N(DOUBLE(NUM_AXES), - SP_Y_STR, 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, - SP_U_STR, pos.u, SP_V_STR, pos.v, SP_W_STR, pos.w + SP_X_LBL, pos.x, SP_Y_LBL, pos.y, SP_Z_LBL, pos.z, + SP_I_LBL, pos.i, SP_J_LBL, pos.j, SP_K_LBL, pos.k, + SP_U_LBL, pos.u, SP_V_LBL, pos.v, SP_W_LBL, pos.w ) #if HAS_EXTRUDERS - , SP_E_STR, pos.e + , SP_E_LBL, pos.e #endif ); } diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index b59e93ac0783..b85487af45c2 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -68,7 +68,7 @@ void GcodeSuite::G61() { SYNC_E(stored_position[slot].e); } else { - if (parser.seen(NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W))) { + if (parser.seen(STR_AXES_MAIN)) { DEBUG_ECHOPGM(STR_RESTORING_POS " S", slot); LOOP_NUM_AXES(i) { destination[i] = parser.seenval(AXIS_CHAR(i)) diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 4fd08489d39a..c42db203b675 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -34,7 +34,7 @@ #include "../../../module/tool_change.h" #endif -#if ENABLED(HAS_PRUSA_MMU2) +#if HAS_PRUSA_MMU2 #include "../../../feature/mmu/mmu2.h" #if ENABLED(MMU2_MENUS) #include "../../../lcd/menu/menu_mmu2.h" diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index 1629a154bce3..5466b6e127d6 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -35,8 +35,6 @@ #include "../../../lcd/e3v2/creality/dwin.h" #elif ENABLED(DWIN_LCD_PROUI) #include "../../../lcd/e3v2/proui/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "../../../lcd/e3v2/jyersui/dwin.h" // Temporary fix until it can be better implemented #endif #define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY) @@ -71,8 +69,6 @@ void GcodeSuite::M1000() { ui.goto_screen(menu_job_recovery); #elif HAS_DWIN_E3V2_BASIC recovery.dwin_flag = true; - #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) // Temporary fix until it can be better implemented - CrealityDWIN.Popup_Handler(Resume); #elif ENABLED(EXTENSIBLE_UI) ExtUI::onPowerLossResume(); #else diff --git a/Marlin/src/gcode/feature/trinamic/M919.cpp b/Marlin/src/gcode/feature/trinamic/M919.cpp index fa349e7f163b..0e9343f6999d 100644 --- a/Marlin/src/gcode/feature/trinamic/M919.cpp +++ b/Marlin/src/gcode/feature/trinamic/M919.cpp @@ -169,6 +169,15 @@ void GcodeSuite::M919() { #if AXIS_IS_TMC(K) case K_AXIS: TMC_SET_CHOPPER_TIME(K); break; #endif + #if AXIS_IS_TMC(U) + case U_AXIS: TMC_SET_CHOPPER_TIME(U); break; + #endif + #if AXIS_IS_TMC(V) + case V_AXIS: TMC_SET_CHOPPER_TIME(V); break; + #endif + #if AXIS_IS_TMC(W) + case W_AXIS: TMC_SET_CHOPPER_TIME(W); break; + #endif #if HAS_E_CHOPPER case E_AXIS: { @@ -236,6 +245,15 @@ void GcodeSuite::M919() { #if AXIS_IS_TMC(K) TMC_SAY_CHOPPER_TIME(K); #endif + #if AXIS_IS_TMC(U) + TMC_SAY_CHOPPER_TIME(U); + #endif + #if AXIS_IS_TMC(V) + TMC_SAY_CHOPPER_TIME(V); + #endif + #if AXIS_IS_TMC(W) + TMC_SAY_CHOPPER_TIME(W); + #endif #if AXIS_IS_TMC(E0) TMC_SAY_CHOPPER_TIME(E0); #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index b8668c74a856..a13940afc326 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -21,7 +21,7 @@ */ /** - * gcode.cpp - Temporary container for all gcode handlers + * gcode.cpp - Temporary container for all G-code handlers * Most will migrate to classes, by feature. */ @@ -53,7 +53,7 @@ GcodeSuite gcode; #include "../feature/cancel_object.h" #endif -#if ENABLED(LASER_MOVE_POWER) +#if ENABLED(LASER_FEATURE) #include "../feature/spindle_laser.h" #endif @@ -73,8 +73,11 @@ GcodeSuite gcode; // Inactivity shutdown millis_t GcodeSuite::previous_move_ms = 0, - GcodeSuite::max_inactive_time = 0, - GcodeSuite::stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_DEACTIVE_TIME); + GcodeSuite::max_inactive_time = 0; + +#if HAS_DISABLE_INACTIVE_AXIS + millis_t GcodeSuite::stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_DEACTIVE_TIME); +#endif // Relative motion mode for each logical axis static constexpr xyze_bool_t ar_init = AXIS_RELATIVE_MODES; @@ -207,8 +210,11 @@ void GcodeSuite::get_destination_from_command() { recovery.save(); #endif - if (parser.floatval('F') > 0) + if (parser.floatval('F') > 0) { feedrate_mm_s = parser.value_feedrate(); + // Update the cutter feed rate for use by M4 I set inline moves. + TERN_(LASER_FEATURE, cutter.feedrate_mm_m = MMS_TO_MMM(feedrate_mm_s)); + } #if BOTH(PRINTCOUNTER, HAS_EXTRUDERS) if (!DEBUGGING(DRYRUN) && !skip_move) @@ -220,15 +226,29 @@ void GcodeSuite::get_destination_from_command() { M165(); #endif - #if ENABLED(LASER_MOVE_POWER) - // Set the laser power in the planner to configure this move - if (parser.seen('S')) { - const float spwr = parser.value_float(); - cutter.inline_power(TERN(SPINDLE_LASER_USE_PWM, cutter.power_to_range(cutter_power_t(round(spwr))), spwr > 0 ? 255 : 0)); + #if ENABLED(LASER_FEATURE) + if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS || cutter.cutter_mode == CUTTER_MODE_DYNAMIC) { + // Set the cutter power in the planner to configure this move + cutter.last_feedrate_mm_m = 0; + if (WITHIN(parser.codenum, 1, TERN(ARC_SUPPORT, 3, 1)) || TERN0(BEZIER_CURVE_SUPPORT, parser.codenum == 5)) { + planner.laser_inline.status.isPowered = true; + if (parser.seen('I')) cutter.set_enabled(true); // This is set for backward LightBurn compatibility. + if (parser.seen('S')) { + const float v = parser.value_float(), + u = TERN(LASER_POWER_TRAP, v, cutter.power_to_range(v)); + cutter.menuPower = cutter.unitPower = u; + cutter.inline_power(TERN(SPINDLE_LASER_USE_PWM, cutter.upower_to_ocr(u), u > 0 ? 255 : 0)); + } + } + else if (parser.codenum == 0) { + // For dynamic mode we need to flag isPowered off, dynamic power is calculated in the stepper based on feedrate. + if (cutter.cutter_mode == CUTTER_MODE_DYNAMIC) planner.laser_inline.status.isPowered = false; + cutter.inline_power(0); // This is planner-based so only set power and do not disable inline control flags. + } } - else if (ENABLED(LASER_MOVE_G0_OFF) && parser.codenum == 0) // G0 - cutter.set_inline_enabled(false); - #endif + else if (parser.codenum == 0) + cutter.apply_power(0); + #endif // LASER_FEATURE } /** @@ -845,6 +865,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 421: M421(); break; // M421: Set a Mesh Bed Leveling Z coordinate #endif + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + case 423: M423(); break; // M423: Reset, modify, or report X-Twist Compensation data + #endif + #if ENABLED(BACKLASH_GCODE) case 425: M425(); break; // M425: Tune backlash compensation #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 215d0d4f9b92..1efcb1cf9345 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -110,7 +110,7 @@ * M33 - Get the longname version of a path. (Requires LONG_FILENAME_HOST_SUPPORT) * M34 - Set SD Card sorting options. (Requires SDCARD_SORT_ALPHA) * - * M42 - Change pin status via gcode: M42 P S. LED pin assumed if P is omitted. (Requires DIRECT_PIN_CONTROL) + * M42 - Change pin status via G-code: M42 P S. LED pin assumed if P is omitted. (Requires DIRECT_PIN_CONTROL) * M43 - Display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins (Requires PINS_DEBUGGING) * M48 - Measure Z Probe repeatability: M48 P X Y V E L S. (Requires Z_MIN_PROBE_REPEATABILITY_TEST) * @@ -396,14 +396,20 @@ class GcodeSuite { static bool select_coordinate_system(const int8_t _new); #endif - static millis_t previous_move_ms, max_inactive_time, stepper_inactive_time; - FORCE_INLINE static void reset_stepper_timeout(const millis_t ms=millis()) { previous_move_ms = ms; } + static millis_t previous_move_ms, max_inactive_time; FORCE_INLINE static bool stepper_max_timed_out(const millis_t ms=millis()) { return max_inactive_time && ELAPSED(ms, previous_move_ms + max_inactive_time); } - FORCE_INLINE static bool stepper_inactive_timeout(const millis_t ms=millis()) { - return ELAPSED(ms, previous_move_ms + stepper_inactive_time); - } + FORCE_INLINE static void reset_stepper_timeout(const millis_t ms=millis()) { previous_move_ms = ms; } + + #if HAS_DISABLE_INACTIVE_AXIS + static millis_t stepper_inactive_time; + FORCE_INLINE static bool stepper_inactive_timeout(const millis_t ms=millis()) { + return ELAPSED(ms, previous_move_ms + stepper_inactive_time); + } + #else + static bool stepper_inactive_timeout(const millis_t) { return false; } + #endif static void report_echo_start(const bool forReplay); static void report_heading(const bool forReplay, FSTR_P const fstr, const bool eol=true); diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 2dd1de00013b..2ebe38bbcf19 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -214,7 +214,7 @@ void GcodeSuite::D(const int16_t dcode) { c = 1024 * 4; while (c--) { - TERN_(USE_WATCHDOG, watchdog_refresh()); + hal.watchdog_refresh(); card.write(buf, COUNT(buf)); } SERIAL_ECHOLNPGM(" done"); @@ -231,7 +231,7 @@ void GcodeSuite::D(const int16_t dcode) { __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; uint16_t c = 1024 * 4; while (c--) { - TERN_(USE_WATCHDOG, watchdog_refresh()); + hal.watchdog_refresh(); card.read(buf, COUNT(buf)); bool error = false; for (uint16_t i = 0; i < COUNT(buf); i++) { diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 6e14cc4df915..58ed26a15aa8 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -93,7 +93,7 @@ void GcodeSuite::G92() { 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 HAS_POSITION_SHIFT && !IS_SCARA // When using workspaces... + #if HAS_POSITION_SHIFT && NONE(IS_SCARA, POLARGRAPH) // When using workspaces... if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) { position_shift[i] += d; // ...most axes offset the workspace... update_workspace_offset((AxisEnum)i); diff --git a/Marlin/src/gcode/lcd/M73.cpp b/Marlin/src/gcode/lcd/M73.cpp index 355445c573b9..a86eee4d9967 100644 --- a/Marlin/src/gcode/lcd/M73.cpp +++ b/Marlin/src/gcode/lcd/M73.cpp @@ -42,7 +42,7 @@ void GcodeSuite::M73() { #if ENABLED(DWIN_LCD_PROUI) - DWIN_Progress_Update(); + DWIN_M73(); #else diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index d647894d2774..933bf3d5d9ef 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -92,7 +92,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves if (fwretract.autoretract_enabled && parser.seen_test('E') - && !parser.seen(NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W)) + && !parser.seen(STR_AXES_MAIN) ) { const float echange = destination.e - current_position.e; // Is this a retract or recover move? diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index dd1c1d14708f..14ef9ac2a6f4 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -197,8 +197,8 @@ void plan_arc( // Feedrate for the move, scaled by the feedrate multiplier const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); - // Get the nominal segment length based on settings - const float nominal_segment_mm = ( + // Get the ideal segment length for the move based on settings + const float ideal_segment_mm = ( #if ARC_SEGMENTS_PER_SEC // Length based on segments per second and feedrate constrain(scaled_fr_mm_s * RECIPROCAL(ARC_SEGMENTS_PER_SEC), MIN_ARC_SEGMENT_MM, MAX_ARC_SEGMENT_MM) #else @@ -206,19 +206,18 @@ void plan_arc( #endif ); - // Number of whole segments based on the nominal segment length - const float nominal_segments = _MAX(FLOOR(flat_mm / nominal_segment_mm), min_segments); + // Number of whole segments based on the ideal segment length + const float nominal_segments = _MAX(FLOOR(flat_mm / ideal_segment_mm), min_segments), + nominal_segment_mm = flat_mm / nominal_segments; - // A new segment length based on the required minimum - const float segment_mm = constrain(flat_mm / nominal_segments, MIN_ARC_SEGMENT_MM, MAX_ARC_SEGMENT_MM); + // The number of whole segments in the arc, with best attempt to honor MIN_ARC_SEGMENT_MM and MAX_ARC_SEGMENT_MM + const uint16_t segments = nominal_segment_mm > (MAX_ARC_SEGMENT_MM) ? CEIL(flat_mm / (MAX_ARC_SEGMENT_MM)) : + nominal_segment_mm < (MIN_ARC_SEGMENT_MM) ? _MAX(1, FLOOR(flat_mm / (MIN_ARC_SEGMENT_MM))) : + nominal_segments; - // The number of whole segments in the arc, ignoring the remainder - uint16_t segments = FLOOR(flat_mm / segment_mm); - - // Are the segments now too few to reach the destination? - const float segmented_length = segment_mm * segments; - const bool tooshort = segmented_length < flat_mm - 0.0001f; - const float proportion = tooshort ? segmented_length / flat_mm : 1.0f; + #if ENABLED(SCARA_FEEDRATE_SCALING) + const float inv_duration = (scaled_fr_mm_s / flat_mm) * segments; + #endif /** * Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, @@ -246,108 +245,106 @@ void plan_arc( * a correction, the planner should have caught up to the lag caused by the initial plan_arc overhead. * This is important when there are successive arc motions. */ - // Vector rotation matrix values - xyze_pos_t raw; - const float theta_per_segment = proportion * angular_travel / segments, - sq_theta_per_segment = sq(theta_per_segment), - 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 DISABLED(AUTO_BED_LEVELING_UBL) - ARC_LIJKUVW_CODE( - const float per_segment_L = proportion * travel_L / segments, - const float per_segment_I = proportion * travel_I / segments, - const float per_segment_J = proportion * travel_J / segments, - const float per_segment_K = proportion * travel_K / segments, - const float per_segment_U = proportion * travel_U / segments, - const float per_segment_V = proportion * travel_V / segments, - const float per_segment_W = proportion * travel_W / segments - ); - #endif - CODE_ITEM_E(const float extruder_per_segment = proportion * travel_E / segments); - - // For shortened segments, run all but the remainder in the loop - if (tooshort) segments++; + xyze_pos_t raw; - // Initialize all linear axes and E - ARC_LIJKUVWE_CODE( - raw[axis_l] = current_position[axis_l], - raw.i = current_position.i, - raw.j = current_position.j, - raw.k = current_position.k, - raw.u = current_position.u, - raw.v = current_position.v, - raw.w = current_position.w, - raw.e = current_position.e - ); + // do not calculate rotation parameters for trivial single-segment arcs + if (segments > 1) { + // Vector rotation matrix values + const float theta_per_segment = angular_travel / segments, + sq_theta_per_segment = sq(theta_per_segment), + 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 DISABLED(AUTO_BED_LEVELING_UBL) + ARC_LIJKUVW_CODE( + const float per_segment_L = travel_L / segments, + const float per_segment_I = travel_I / segments, + const float per_segment_J = travel_J / segments, + const float per_segment_K = travel_K / segments, + const float per_segment_U = travel_U / segments, + const float per_segment_V = travel_V / segments, + const float per_segment_W = travel_W / segments + ); + #endif - #if ENABLED(SCARA_FEEDRATE_SCALING) - const float inv_duration = scaled_fr_mm_s / segment_mm; - #endif + CODE_ITEM_E(const float extruder_per_segment = travel_E / segments); - millis_t next_idle_ms = millis() + 200UL; + // Initialize all linear axes and E + ARC_LIJKUVWE_CODE( + raw[axis_l] = current_position[axis_l], + raw.i = current_position.i, + raw.j = current_position.j, + raw.k = current_position.k, + raw.u = current_position.u, + raw.v = current_position.v, + raw.w = current_position.w, + raw.e = current_position.e + ); - #if N_ARC_CORRECTION > 1 - int8_t arc_recalc_count = N_ARC_CORRECTION; - #endif + millis_t next_idle_ms = millis() + 200UL; - for (uint16_t i = 1; i < segments; i++) { // Iterate (segments-1) times + #if N_ARC_CORRECTION > 1 + int8_t arc_recalc_count = N_ARC_CORRECTION; + #endif - thermalManager.manage_heater(); - const millis_t ms = millis(); - if (ELAPSED(ms, next_idle_ms)) { - next_idle_ms = ms + 200UL; - idle(); - } + for (uint16_t i = 1; i < segments; i++) { // Iterate (segments-1) times - #if N_ARC_CORRECTION > 1 - if (--arc_recalc_count) { - // Apply vector rotation matrix to previous rvec.a / 1 - const float r_new_Y = rvec.a * sin_T + rvec.b * cos_T; - rvec.a = rvec.a * cos_T - rvec.b * sin_T; - rvec.b = r_new_Y; + thermalManager.task(); + const millis_t ms = millis(); + if (ELAPSED(ms, next_idle_ms)) { + next_idle_ms = ms + 200UL; + idle(); } - else - #endif - { + #if N_ARC_CORRECTION > 1 - arc_recalc_count = N_ARC_CORRECTION; + if (--arc_recalc_count) { + // Apply vector rotation matrix to previous rvec.a / 1 + const float r_new_Y = rvec.a * sin_T + rvec.b * cos_T; + rvec.a = rvec.a * cos_T - rvec.b * sin_T; + rvec.b = r_new_Y; + } + else #endif + { + #if N_ARC_CORRECTION > 1 + arc_recalc_count = N_ARC_CORRECTION; + #endif + + // Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. + // Compute exact location by applying transformation matrix from initial radius vector(=-offset). + // To reduce stuttering, the sin and cos could be computed at different times. + // For now, compute both at the same time. + const float Ti = i * theta_per_segment, cos_Ti = cos(Ti), sin_Ti = sin(Ti); + rvec.a = -offset[0] * cos_Ti + offset[1] * sin_Ti; + rvec.b = -offset[0] * sin_Ti - offset[1] * cos_Ti; + } - // Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. - // Compute exact location by applying transformation matrix from initial radius vector(=-offset). - // To reduce stuttering, the sin and cos could be computed at different times. - // For now, compute both at the same time. - const float cos_Ti = cos(i * theta_per_segment), sin_Ti = sin(i * theta_per_segment); - rvec.a = -offset[0] * cos_Ti + offset[1] * sin_Ti; - rvec.b = -offset[0] * sin_Ti - offset[1] * cos_Ti; - } - - // Update raw location - raw[axis_p] = center_P + rvec.a; - raw[axis_q] = center_Q + rvec.b; - ARC_LIJKUVWE_CODE( - #if ENABLED(AUTO_BED_LEVELING_UBL) - raw[axis_l] = start_L, - raw.i = start_I, raw.j = start_J, raw.k = start_K, - raw.u = start_U, raw.v = start_V, raw.w = start_V - #else - raw[axis_l] += per_segment_L, - raw.i += per_segment_I, raw.j += per_segment_J, raw.k += per_segment_K, - raw.u += per_segment_U, raw.v += per_segment_V, raw.w += per_segment_W - #endif - , raw.e += extruder_per_segment - ); + // Update raw location + raw[axis_p] = center_P + rvec.a; + raw[axis_q] = center_Q + rvec.b; + ARC_LIJKUVWE_CODE( + #if ENABLED(AUTO_BED_LEVELING_UBL) + raw[axis_l] = start_L, + raw.i = start_I, raw.j = start_J, raw.k = start_K, + raw.u = start_U, raw.v = start_V, raw.w = start_V + #else + raw[axis_l] += per_segment_L, + raw.i += per_segment_I, raw.j += per_segment_J, raw.k += per_segment_K, + raw.u += per_segment_U, raw.v += per_segment_V, raw.w += per_segment_W + #endif + , raw.e += extruder_per_segment + ); - apply_motion_limits(raw); + apply_motion_limits(raw); - #if HAS_LEVELING && !PLANNER_LEVELING - planner.apply_leveling(raw); - #endif + #if HAS_LEVELING && !PLANNER_LEVELING + planner.apply_leveling(raw); + #endif - if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) - break; + if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) + break; + } } // Ensure last segment arrives at target location. diff --git a/Marlin/src/gcode/motion/G6.cpp b/Marlin/src/gcode/motion/G6.cpp index a57a293e06f8..fb6281707b45 100644 --- a/Marlin/src/gcode/motion/G6.cpp +++ b/Marlin/src/gcode/motion/G6.cpp @@ -50,7 +50,7 @@ void GcodeSuite::G6() { // No speed is set, can't schedule the move if (!planner.last_page_step_rate) return; - const page_idx_t page_idx = (page_idx_t) parser.value_ulong(); + const page_idx_t page_idx = (page_idx_t)parser.value_ulong(); uint16_t num_steps = DirectStepping::Config::TOTAL_STEPS; if (parser.seen('S')) num_steps = parser.value_ushort(); diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 8185bf8f78b4..4fe83ccd4079 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -87,7 +87,7 @@ void GcodeSuite::M290() { } #endif - if (!parser.seen(NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W)) || parser.seen('R')) { + if (!parser.seen(STR_AXES_MAIN) || parser.seen('R')) { SERIAL_ECHO_START(); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) @@ -111,7 +111,7 @@ void GcodeSuite::M290() { #endif #if ENABLED(MESH_BED_LEVELING) - SERIAL_ECHOLNPGM("MBL Adjust Z", mbl.z_offset); + SERIAL_ECHOLNPGM("MBL Adjust Z", bedlevel.z_offset); #endif #if ENABLED(BABYSTEP_DISPLAY_TOTAL) diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index c91a0de5f219..3f5290e81c67 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -45,7 +45,7 @@ /** * GCode parser * - * - Parse a single gcode line for its letter, code, subcode, and parameters + * - Parse a single G-code line for its letter, code, subcode, and parameters * - FASTER_GCODE_PARSER: * - Flags existing params (1 bit each) * - Stores value offsets (1 byte each) @@ -225,7 +225,7 @@ class GCodeParser { #endif // !FASTER_GCODE_PARSER // Seen any axis parameter - static bool seen_axis() { return seen(LOGICAL_AXES_STRING); } + static bool seen_axis() { return seen(STR_AXES_LOGICAL); } #if ENABLED(GCODE_QUOTED_STRINGS) static char* unescape_string(char* &src); diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index 474f1f252a04..a16853bdf894 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -33,6 +33,10 @@ #include "../../feature/probe_temp_comp.h" #endif +#if ENABLED(DWIN_LCD_PROUI) + #include "../../lcd/marlinui.h" +#endif + /** * G30: Do a single Z probe at the current XY * @@ -48,20 +52,38 @@ void GcodeSuite::G30() { const xy_pos_t pos = { parser.linearval('X', current_position.x + probe.offset_xy.x), parser.linearval('Y', current_position.y + probe.offset_xy.y) }; - if (!probe.can_reach(pos)) return; + if (!probe.can_reach(pos)) { + #if ENABLED(DWIN_LCD_PROUI) + SERIAL_ECHOLNF(GET_EN_TEXT_F(MSG_ZPROBE_OUT)); + LCD_MESSAGE(MSG_ZPROBE_OUT); + #endif + return; + } // Disable leveling so the planner won't mess with us TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); remember_feedrate_scaling_off(); + TERN_(DWIN_LCD_PROUI, process_subcommands_now(F("G28O"))); + const ProbePtRaise raise_after = parser.boolval('E', true) ? PROBE_PT_STOW : PROBE_PT_NONE; TERN_(HAS_PTC, ptc.set_enabled(!parser.seen('C') || parser.value_bool())); const float measured_z = probe.probe_at_point(pos, raise_after, 1); TERN_(HAS_PTC, ptc.set_enabled(true)); - if (!isnan(measured_z)) + if (!isnan(measured_z)) { SERIAL_ECHOLNPGM("Bed X: ", pos.x, " Y: ", pos.y, " Z: ", measured_z); + #if ENABLED(DWIN_LCD_PROUI) + char msg[31], str_1[6], str_2[6], str_3[6]; + sprintf_P(msg, PSTR("X:%s, Y:%s, Z:%s"), + dtostrf(pos.x, 1, 1, str_1), + dtostrf(pos.y, 1, 1, str_2), + dtostrf(measured_z, 1, 2, str_3) + ); + ui.set_status(msg); + #endif + } restore_feedrate_and_scaling(); diff --git a/Marlin/src/gcode/probe/M951.cpp b/Marlin/src/gcode/probe/M951.cpp index c6a9cfbe206c..7a06400e3336 100644 --- a/Marlin/src/gcode/probe/M951.cpp +++ b/Marlin/src/gcode/probe/M951.cpp @@ -32,13 +32,13 @@ mpe_settings_t mpe_settings; inline void mpe_settings_report() { SERIAL_ECHO_MSG("Magnetic Parking Extruder"); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("L: Left parking :", mpe_settings.parking_xpos[0]); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("R: Right parking :", mpe_settings.parking_xpos[1]); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("I: Grab Offset :", mpe_settings.grab_distance); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("J: Normal speed :", long(MMS_TO_MMM(mpe_settings.slow_feedrate))); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("H: High speed :", long(MMS_TO_MMM(mpe_settings.fast_feedrate))); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("D: Distance trav.:", mpe_settings.travel_distance); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("C: Compenstion :", mpe_settings.compensation_factor); + SERIAL_ECHO_MSG("L: Left parking :", mpe_settings.parking_xpos[0]); + SERIAL_ECHO_MSG("R: Right parking :", mpe_settings.parking_xpos[1]); + SERIAL_ECHO_MSG("I: Grab Offset :", mpe_settings.grab_distance); + SERIAL_ECHO_MSG("J: Normal speed :", long(MMS_TO_MMM(mpe_settings.slow_feedrate))); + SERIAL_ECHO_MSG("H: High speed :", long(MMS_TO_MMM(mpe_settings.fast_feedrate))); + SERIAL_ECHO_MSG("D: Distance trav.:", mpe_settings.travel_distance); + SERIAL_ECHO_MSG("C: Compenstion :", mpe_settings.compensation_factor); } void mpe_settings_init() { diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 2250cd3b7452..a390a46d8e31 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -196,14 +196,15 @@ bool GCodeQueue::process_injected_command() { * Never call this from a G-code handler! */ void GCodeQueue::enqueue_one_now(const char * const cmd) { while (!enqueue_one(cmd)) idle(); } +void GCodeQueue::enqueue_one_now(FSTR_P const fcmd) { while (!enqueue_one(fcmd)) idle(); } /** * Attempt to enqueue a single G-code command * and return 'true' if successful. */ -bool GCodeQueue::enqueue_one(FSTR_P const fgcode) { +bool GCodeQueue::enqueue_one(FSTR_P const fcmd) { size_t i = 0; - PGM_P p = FTOP(fgcode); + PGM_P p = FTOP(fcmd); char c; while ((c = pgm_read_byte(&p[i])) && c != '\n') i++; char cmd[i + 1]; @@ -383,7 +384,7 @@ inline bool process_line_done(uint8_t &sis, char (&buff)[MAX_CMD_SIZE], int &ind 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 + thermalManager.task(); // Keep sensors satisfied else ind = 0; // Start a new line return is_empty; // Inform the caller diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 1a2baaa6bbc4..142283008001 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -141,12 +141,13 @@ class GCodeQueue { * Enqueue and return only when commands are actually enqueued */ static void enqueue_one_now(const char * const cmd); + static void enqueue_one_now(FSTR_P const fcmd); /** * Attempt to enqueue a single G-code command * and return 'true' if successful. */ - static bool enqueue_one(FSTR_P const fgcode); + static bool enqueue_one(FSTR_P const fcmd); /** * Enqueue with Serial Echo diff --git a/Marlin/src/gcode/stats/M31.cpp b/Marlin/src/gcode/stats/M31.cpp index 355701f6a413..1a1c13ba2f1a 100644 --- a/Marlin/src/gcode/stats/M31.cpp +++ b/Marlin/src/gcode/stats/M31.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M31() { char buffer[22]; duration_t(print_job_timer.duration()).toString(buffer); - ui.set_status(buffer); + ui.set_status(buffer, ENABLED(DWIN_LCD_PROUI)); SERIAL_ECHO_MSG("Print time: ", buffer); } diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index 98e87c415de9..ae517c977b29 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -90,7 +90,7 @@ void GcodeSuite::M106() { // Set speed, with constraint thermalManager.set_fan_speed(pfan, speed); - TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS)); + TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_BIT_SYNC_FANS)); if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating thermalManager.set_fan_speed(1 - pfan, speed); @@ -111,7 +111,7 @@ void GcodeSuite::M107() { 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)); + TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_BIT_SYNC_FANS)); } #endif // HAS_FAN diff --git a/Marlin/src/gcode/temp/M306.cpp b/Marlin/src/gcode/temp/M306.cpp index 0f286e73b236..7978922ff4c0 100644 --- a/Marlin/src/gcode/temp/M306.cpp +++ b/Marlin/src/gcode/temp/M306.cpp @@ -36,6 +36,7 @@ * C Block heat capacity. * E Extruder number to set. (Default: E0) * F Ambient heat transfer coefficient (fan on full). + * H Filament heat capacity per mm. * P Heater power. * R Sensor responsiveness (= transfer coefficient / heat capcity). */ @@ -43,7 +44,7 @@ void GcodeSuite::M306() { if (parser.seen_test('T')) { thermalManager.MPC_autotune(); return; } - if (parser.seen("ACFPR")) { + if (parser.seen("ACFPRH")) { const heater_id_t hid = (heater_id_t)parser.intval('E', 0); MPC_t &constants = thermalManager.temp_hotend[hid].constants; if (parser.seenval('P')) constants.heater_power = parser.value_float(); @@ -53,6 +54,7 @@ void GcodeSuite::M306() { #if ENABLED(MPC_INCLUDE_FAN) if (parser.seenval('F')) constants.fan255_adjustment = parser.value_float() - constants.ambient_xfer_coeff_fan0; #endif + if (parser.seenval('H')) constants.filament_heat_capacity_permm = parser.value_float(); return; } @@ -70,8 +72,10 @@ void GcodeSuite::M306_report(const bool forReplay/*=true*/) { SERIAL_ECHOPAIR_F(" R", constants.sensor_responsiveness, 4); SERIAL_ECHOPAIR_F(" A", constants.ambient_xfer_coeff_fan0, 4); #if ENABLED(MPC_INCLUDE_FAN) - SERIAL_ECHOLNPAIR_F(" F", constants.ambient_xfer_coeff_fan0 + constants.fan255_adjustment, 4); + SERIAL_ECHOPAIR_F(" F", constants.ambient_xfer_coeff_fan0 + constants.fan255_adjustment, 4); #endif + SERIAL_ECHOPAIR_F(" H", constants.filament_heat_capacity_permm, 4); + SERIAL_EOL(); } } diff --git a/Marlin/src/gcode/units/M149.cpp b/Marlin/src/gcode/units/M149.cpp index 3f1ea3654ec4..a04247cbcb17 100644 --- a/Marlin/src/gcode/units/M149.cpp +++ b/Marlin/src/gcode/units/M149.cpp @@ -30,9 +30,9 @@ * M149: Set temperature units */ void GcodeSuite::M149() { - if (parser.seenval('C')) parser.set_input_temp_units(TEMPUNIT_C); - else if (parser.seenval('K')) parser.set_input_temp_units(TEMPUNIT_K); - else if (parser.seenval('F')) parser.set_input_temp_units(TEMPUNIT_F); + if (parser.seen('C')) parser.set_input_temp_units(TEMPUNIT_C); + else if (parser.seen('K')) parser.set_input_temp_units(TEMPUNIT_K); + else if (parser.seen('F')) parser.set_input_temp_units(TEMPUNIT_F); else M149_report(); } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 95647d100e25..fc66f5359ccd 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -99,11 +99,10 @@ #define IS_ULTIPANEL 1 #define STD_ENCODER_PULSES_PER_STEP 2 -#elif ANY(miniVIKI, VIKI2, WYH_L12864, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864) - - #define IS_DOGM_12864 1 +#elif ANY(miniVIKI, VIKI2, WYH_L12864, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, EMOTION_TECH_LCD) #define DOGLCD + #define IS_DOGM_12864 1 #define IS_ULTIPANEL 1 #if ENABLED(miniVIKI) @@ -117,6 +116,9 @@ #define IS_U8GLIB_LM6059_AF 1 #elif ENABLED(AZSMZ_12864) #define IS_U8GLIB_ST7565_64128N 1 + #elif ENABLED(EMOTION_TECH_LCD) + #define IS_U8GLIB_ST7565_64128N 1 + #define ST7565_VOLTAGE_DIVIDER_VALUE 0x07 #endif #elif ENABLED(OLED_PANEL_TINYBOY2) @@ -475,8 +477,6 @@ // Aliases for LCD features #if EITHER(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) #define HAS_DWIN_E3V2_BASIC 1 -#endif -#if EITHER(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) #define HAS_DWIN_E3V2 1 #endif #if ENABLED(DWIN_LCD_PROUI) @@ -486,15 +486,6 @@ // E3V2 extras #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI #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_MINI_E3_V3_0, BTT_SKR_E3_TURBO) - #define LCD_SERIAL_PORT 1 - #elif MB(CREALITY_V24S1_301) - #define LCD_SERIAL_PORT 2 // Creality Ender3S1 board - #else - #define LCD_SERIAL_PORT 3 // Creality 4.x board - #endif - #endif #define HAS_LCD_BRIGHTNESS 1 #define LCD_BRIGHTNESS_MAX 250 #if ENABLED(DWIN_LCD_PROUI) @@ -515,7 +506,7 @@ #endif #endif -#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) +#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI) #define HAS_DISPLAY 1 #endif @@ -523,7 +514,7 @@ #define HAS_LCDPRINT 1 #endif -#if ANY(HAS_DISPLAY, HAS_DWIN_E3V2) +#if HAS_DISPLAY || HAS_DWIN_E3V2 #define HAS_STATUS_MESSAGE 1 #endif @@ -535,7 +526,7 @@ #define HAS_MANUAL_MOVE_MENU 1 #endif -#if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL, IS_DWIN_MARLINUI, DWIN_CREALITY_LCD_JYERSUI) +#if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL, IS_DWIN_MARLINUI) #define CAN_SHOW_REMAINING_TIME 1 #endif @@ -679,13 +670,43 @@ * Number of Linear Axes (e.g., XYZIJKUVW) * All the logical axes except for the tool (E) axis */ -#ifndef NUM_AXES - #define NUM_AXES XYZ +#ifdef NUM_AXES + #undef NUM_AXES + #define NUM_AXES_WARNING 1 +#endif + +#ifdef W_DRIVER_TYPE + #define NUM_AXES 9 +#elif defined(V_DRIVER_TYPE) + #define NUM_AXES 8 +#elif defined(U_DRIVER_TYPE) + #define NUM_AXES 7 +#elif defined(K_DRIVER_TYPE) + #define NUM_AXES 6 +#elif defined(J_DRIVER_TYPE) + #define NUM_AXES 5 +#elif defined(I_DRIVER_TYPE) + #define NUM_AXES 4 +#elif defined(Z_DRIVER_TYPE) + #define NUM_AXES 3 +#elif defined(Y_DRIVER_TYPE) + #define NUM_AXES 2 +#else + #define NUM_AXES 1 #endif #if NUM_AXES >= XY #define HAS_Y_AXIS 1 #if NUM_AXES >= XYZ #define HAS_Z_AXIS 1 + #ifdef Z4_DRIVER_TYPE + #define NUM_Z_STEPPERS 4 + #elif defined(Z3_DRIVER_TYPE) + #define NUM_Z_STEPPERS 3 + #elif defined(Z2_DRIVER_TYPE) + #define NUM_Z_STEPPERS 2 + #else + #define NUM_Z_STEPPERS 1 + #endif #if NUM_AXES >= 4 #define HAS_I_AXIS 1 #if NUM_AXES >= 5 @@ -707,6 +728,156 @@ #endif #endif +#if E_STEPPERS <= 0 + #undef E0_DRIVER_TYPE +#endif +#if E_STEPPERS <= 1 + #undef E1_DRIVER_TYPE +#endif +#if E_STEPPERS <= 2 + #undef E2_DRIVER_TYPE +#endif +#if E_STEPPERS <= 3 + #undef E3_DRIVER_TYPE +#endif +#if E_STEPPERS <= 4 + #undef E4_DRIVER_TYPE +#endif +#if E_STEPPERS <= 5 + #undef E5_DRIVER_TYPE +#endif +#if E_STEPPERS <= 6 + #undef E6_DRIVER_TYPE +#endif +#if E_STEPPERS <= 7 + #undef E7_DRIVER_TYPE +#endif + +#if !HAS_Y_AXIS + #undef ENDSTOPPULLUP_YMIN + #undef ENDSTOPPULLUP_YMAX + #undef Y_MIN_ENDSTOP_INVERTING + #undef Y_MAX_ENDSTOP_INVERTING + #undef Y2_DRIVER_TYPE + #undef Y_ENABLE_ON + #undef DISABLE_Y + #undef INVERT_Y_DIR + #undef Y_HOME_DIR + #undef Y_MIN_POS + #undef Y_MAX_POS + #undef MANUAL_Y_HOME_POS +#endif + +#if !HAS_Z_AXIS + #undef ENDSTOPPULLUP_ZMIN + #undef ENDSTOPPULLUP_ZMAX + #undef Z_MIN_ENDSTOP_INVERTING + #undef Z_MAX_ENDSTOP_INVERTING + #undef Z2_DRIVER_TYPE + #undef Z3_DRIVER_TYPE + #undef Z4_DRIVER_TYPE + #undef Z_ENABLE_ON + #undef DISABLE_Z + #undef INVERT_Z_DIR + #undef Z_HOME_DIR + #undef Z_MIN_POS + #undef Z_MAX_POS + #undef MANUAL_Z_HOME_POS +#endif + +#if !HAS_I_AXIS + #undef ENDSTOPPULLUP_IMIN + #undef ENDSTOPPULLUP_IMAX + #undef I_MIN_ENDSTOP_INVERTING + #undef I_MAX_ENDSTOP_INVERTING + #undef I_ENABLE_ON + #undef DISABLE_I + #undef INVERT_I_DIR + #undef I_HOME_DIR + #undef I_MIN_POS + #undef I_MAX_POS + #undef MANUAL_I_HOME_POS +#endif + +#if !HAS_J_AXIS + #undef ENDSTOPPULLUP_JMIN + #undef ENDSTOPPULLUP_JMAX + #undef J_MIN_ENDSTOP_INVERTING + #undef J_MAX_ENDSTOP_INVERTING + #undef J_ENABLE_ON + #undef DISABLE_J + #undef INVERT_J_DIR + #undef J_HOME_DIR + #undef J_MIN_POS + #undef J_MAX_POS + #undef MANUAL_J_HOME_POS +#endif + +#if !HAS_K_AXIS + #undef ENDSTOPPULLUP_KMIN + #undef ENDSTOPPULLUP_KMAX + #undef K_MIN_ENDSTOP_INVERTING + #undef K_MAX_ENDSTOP_INVERTING + #undef K_ENABLE_ON + #undef DISABLE_K + #undef INVERT_K_DIR + #undef K_HOME_DIR + #undef K_MIN_POS + #undef K_MAX_POS + #undef MANUAL_K_HOME_POS +#endif + +#if !HAS_U_AXIS + #undef ENDSTOPPULLUP_UMIN + #undef ENDSTOPPULLUP_UMAX + #undef U_MIN_ENDSTOP_INVERTING + #undef U_MAX_ENDSTOP_INVERTING + #undef U_ENABLE_ON + #undef DISABLE_U + #undef INVERT_U_DIR + #undef U_HOME_DIR + #undef U_MIN_POS + #undef U_MAX_POS + #undef MANUAL_U_HOME_POS +#endif + +#if !HAS_V_AXIS + #undef ENDSTOPPULLUP_VMIN + #undef ENDSTOPPULLUP_VMAX + #undef V_MIN_ENDSTOP_INVERTING + #undef V_MAX_ENDSTOP_INVERTING + #undef V_ENABLE_ON + #undef DISABLE_V + #undef INVERT_V_DIR + #undef V_HOME_DIR + #undef V_MIN_POS + #undef V_MAX_POS + #undef MANUAL_V_HOME_POS +#endif + +#if !HAS_W_AXIS + #undef ENDSTOPPULLUP_WMIN + #undef ENDSTOPPULLUP_WMAX + #undef W_MIN_ENDSTOP_INVERTING + #undef W_MAX_ENDSTOP_INVERTING + #undef W_ENABLE_ON + #undef DISABLE_W + #undef INVERT_W_DIR + #undef W_HOME_DIR + #undef W_MIN_POS + #undef W_MAX_POS + #undef MANUAL_W_HOME_POS +#endif + +#ifdef X2_DRIVER_TYPE + #define HAS_X2_STEPPER 1 + // Dual X Carriage isn't known yet. TODO: Consider moving it to Configuration.h. +#endif +#ifdef Y2_DRIVER_TYPE + #define HAS_Y2_STEPPER 1 + #define HAS_DUAL_Y_STEPPERS 1 +#endif + /** * Number of Primary Linear Axes (e.g., XYZ) * X, XY, or XYZ axes. Excluding duplicate axes (X2, Y2. Z2. Z3, Z4) @@ -876,9 +1047,12 @@ #endif /** - * Set a flag for any type of bed probe, including the paper-test + * Set flags for any form of bed probe */ -#if ANY(HAS_Z_SERVO_PROBE, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, SOLENOID_PROBE, SENSORLESS_PROBING, RACK_AND_PINION_PROBE, MAGLEV4) +#if ANY(TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, SOLENOID_PROBE, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4, MAG_MOUNTED_PROBE) + #define HAS_STOWABLE_PROBE 1 +#endif +#if ANY(HAS_STOWABLE_PROBE, HAS_Z_SERVO_PROBE, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE) #define HAS_BED_PROBE 1 #endif @@ -1036,13 +1210,13 @@ #if NONE(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, HAS_DELTA_SENSORLESS_PROBING) #define USES_Z_MIN_PROBE_PIN 1 #endif - #if Z_HOME_TO_MIN && TERN1(USES_Z_MIN_PROBE_PIN, ENABLED(USE_PROBE_FOR_Z_HOMING)) + #if Z_HOME_TO_MIN && (DISABLED(USES_Z_MIN_PROBE_PIN) || USE_PROBE_FOR_Z_HOMING) #define HOMING_Z_WITH_PROBE 1 #endif #ifndef Z_PROBE_LOW_POINT #define Z_PROBE_LOW_POINT -5 #endif - #if ENABLED(Z_PROBE_ALLEN_KEY) + #if EITHER(Z_PROBE_ALLEN_KEY, MAG_MOUNTED_PROBE) #define PROBE_TRIGGERED_WHEN_STOWED_TEST 1 // Extra test for Allen Key Probe #endif #if MULTIPLE_PROBING > 1 @@ -1071,7 +1245,7 @@ */ #if ENABLED(AUTO_BED_LEVELING_UBL) #undef LCD_BED_LEVELING - #if ENABLED(DELTA) + #if EITHER(DELTA, SEGMENT_LEVELED_MOVES) #define UBL_SEGMENTED 1 #endif #endif @@ -1214,104 +1388,6 @@ #define HAS_ETHERNET 1 #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 HAS_I_AXIS && !defined(INVERT_I_DIR) - #define INVERT_I_DIR false -#endif -#if HAS_J_AXIS && !defined(INVERT_J_DIR) - #define INVERT_J_DIR false -#endif -#if HAS_K_AXIS && !defined(INVERT_K_DIR) - #define INVERT_K_DIR false -#endif -#if HAS_U_AXIS && !defined(INVERT_U_DIR) - #define INVERT_U_DIR false -#endif -#if HAS_V_AXIS && !defined(INVERT_V_DIR) - #define INVERT_V_DIR false -#endif -#if HAS_W_AXIS && !defined(INVERT_W_DIR) - #define INVERT_W_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 * a ballpark safe margin to prevent wait-forever situation. @@ -1391,7 +1467,8 @@ #elif ENABLED(TFT_RES_1024x600) #define TFT_WIDTH 1024 #define TFT_HEIGHT 600 - #define GRAPHICAL_TFT_UPSCALE 4 + #define GRAPHICAL_TFT_UPSCALE 6 + #define TFT_PIXEL_OFFSET_X 120 #endif // FSMC/SPI TFT Panels using standard HAL/tft/tft_(fsmc|spi|ltdc).h diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 5b70f58cdc60..9931409976b6 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -79,6 +79,10 @@ #define SERVO_DELAY { 50 } #endif +#if !HAS_STOWABLE_PROBE + #undef PROBE_DEPLOY_STOW_MENU +#endif + #if !HAS_EXTRUDERS #define NO_VOLUMETRICS #undef TEMP_SENSOR_0 @@ -650,33 +654,20 @@ #endif // Multiple Z steppers -#ifndef NUM_Z_STEPPER_DRIVERS - #define NUM_Z_STEPPER_DRIVERS 1 -#endif - -// Fallback Stepper Driver types that depend on Configuration_adv.h -#if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) - #define HAS_X2_STEPPER 1 -#else - #undef X2_DRIVER_TYPE -#endif -#if DISABLED(Y_DUAL_STEPPER_DRIVERS) - #undef Y2_DRIVER_TYPE -#endif - -#if NUM_Z_STEPPER_DRIVERS < 4 - #undef Z4_DRIVER_TYPE +#if NUM_Z_STEPPERS < 4 #undef INVERT_Z4_VS_Z_DIR - #if NUM_Z_STEPPER_DRIVERS < 3 - #undef Z3_DRIVER_TYPE + #if NUM_Z_STEPPERS < 3 #undef INVERT_Z3_VS_Z_DIR - #if NUM_Z_STEPPER_DRIVERS < 2 - #undef Z2_DRIVER_TYPE + #if NUM_Z_STEPPERS < 2 #undef INVERT_Z2_VS_Z_DIR #endif #endif #endif +#if defined(X2_DRIVER_TYPE) && DISABLED(DUAL_X_CARRIAGE) + #define HAS_DUAL_X_STEPPERS 1 +#endif + // // Spindle/Laser power display types // Defined here so sanity checks can use them @@ -956,7 +947,7 @@ #undef HOME_Z_FIRST #undef HOMING_Z_WITH_PROBE #undef ENABLE_LEVELING_FADE_HEIGHT - #undef NUM_Z_STEPPER_DRIVERS + #undef NUM_Z_STEPPERS #undef CNC_WORKSPACE_PLANES #if NUM_AXES < 2 #undef STEALTHCHOP_Y @@ -1027,6 +1018,24 @@ #define HAS_USER_ITEM(N) 0 #endif +/** + * LCD_SERIAL_PORT must be defined ahead of HAL.h + */ +#ifndef LCD_SERIAL_PORT + #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI || HAS_DGUS_LCD + #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_E3_TURBO) + #define LCD_SERIAL_PORT 1 + #elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_V423, MKS_ROBIN) + #define LCD_SERIAL_PORT 2 // Creality Ender3S1, MKS Robin + #else + #define LCD_SERIAL_PORT 3 // Other boards + #endif + #endif + #ifdef LCD_SERIAL_PORT + #define AUTO_ASSIGNED_LCD_SERIAL 1 + #endif +#endif + #if !HAS_MULTI_SERIAL #undef MEATPACK_ON_SERIAL_PORT_2 #endif @@ -1039,3 +1048,7 @@ #undef CONFIGURATION_EMBEDDING #define CANNOT_EMBED_CONFIGURATION defined(__AVR__) #endif + +#if ANY(DISABLE_INACTIVE_X, DISABLE_INACTIVE_Y, DISABLE_INACTIVE_Z, DISABLE_INACTIVE_I, DISABLE_INACTIVE_J, DISABLE_INACTIVE_K, DISABLE_INACTIVE_U, DISABLE_INACTIVE_V, DISABLE_INACTIVE_W, DISABLE_INACTIVE_E) + #define HAS_DISABLE_INACTIVE_AXIS 1 +#endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index e1de8b28b06c..dfccd9b8f5c5 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -266,7 +266,7 @@ * No adjustable bed on non-cartesians */ #if IS_KINEMATIC - #undef LEVEL_BED_CORNERS + #undef LCD_BED_TRAMMING #endif /** @@ -517,20 +517,28 @@ #define HAS_SHARED_MEDIA 1 #endif - // Set SD_DETECT_STATE based on hardware if not overridden - #if PIN_EXISTS(SD_DETECT) && !defined(SD_DETECT_STATE) - #if BOTH(HAS_MARLINUI_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 + // Not onboard or custom cable + #if SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION) + #define SD_CONNECTION_TYPICAL 1 + #endif + + // Set SD_DETECT_STATE based on hardware if not overridden + #if PIN_EXISTS(SD_DETECT) + #define HAS_SD_DETECT 1 + #ifndef SD_DETECT_STATE + #if ALL(SD_CONNECTION_TYPICAL, HAS_MARLINUI_MENU, ELB_FULL_GRAPHIC_CONTROLLER) + #define SD_DETECT_STATE HIGH + #else + #define SD_DETECT_STATE LOW + #endif + #endif + #endif + #if DISABLED(USB_FLASH_DRIVE_SUPPORT) || BOTH(MULTI_VOLUME, VOLUME_SD_ONBOARD) #if ENABLED(SDIO_SUPPORT) #define NEED_SD2CARD_SDIO 1 @@ -539,10 +547,10 @@ #endif #endif -#endif + #if HAS_SD_DETECT && NONE(HAS_GRAPHICAL_TFT, LCD_USE_DMA_FSMC, HAS_FSMC_GRAPHICAL_TFT, HAS_SPI_GRAPHICAL_TFT, IS_DWIN_MARLINUI, EXTENSIBLE_UI, HAS_DWIN_E3V2) + #define REINIT_NOISY_LCD 1 // Have the LCD re-init on SD insertion + #endif -#if PIN_EXISTS(SD_DETECT) && NONE(HAS_GRAPHICAL_TFT, LCD_USE_DMA_FSMC, HAS_FSMC_GRAPHICAL_TFT, HAS_SPI_GRAPHICAL_TFT, IS_DWIN_MARLINUI, EXTENSIBLE_UI, HAS_DWIN_E3V2) - #define REINIT_NOISY_LCD 1 // Have the LCD re-init on SD insertion #endif /** @@ -1234,7 +1242,7 @@ #endif #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 #if Z_HOME_TO_MAX #ifndef Z3_MAX_ENDSTOP_INVERTING #if Z3_USE_ENDSTOP == _XMIN_ @@ -1366,7 +1374,7 @@ #endif #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 #if Z_HOME_TO_MAX #ifndef Z4_MAX_ENDSTOP_INVERTING #if Z4_USE_ENDSTOP == _XMIN_ @@ -1675,7 +1683,7 @@ #undef DISABLE_INACTIVE_Z #endif -#if NUM_Z_STEPPER_DRIVERS >= 2 +#if NUM_Z_STEPPERS >= 2 #if PIN_EXISTS(Z2_ENABLE) || AXIS_IS_L64XX(Z2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) #define HAS_Z2_ENABLE 1 #endif @@ -1690,7 +1698,7 @@ #endif #endif -#if NUM_Z_STEPPER_DRIVERS >= 3 +#if NUM_Z_STEPPERS >= 3 #if PIN_EXISTS(Z3_ENABLE) || AXIS_IS_L64XX(Z3) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) #define HAS_Z3_ENABLE 1 #endif @@ -1705,7 +1713,7 @@ #endif #endif -#if NUM_Z_STEPPER_DRIVERS >= 4 +#if NUM_Z_STEPPERS >= 4 #if PIN_EXISTS(Z4_ENABLE) || AXIS_IS_L64XX(Z4) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) #define HAS_Z4_ENABLE 1 #endif @@ -2080,7 +2088,7 @@ #ifndef Y_SLAVE_ADDRESS #define Y_SLAVE_ADDRESS 0 #endif - #if ENABLED(Y_DUAL_STEPPER_DRIVERS) + #if HAS_DUAL_Y_STEPPERS #if defined(Y2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2) #define Y2_SENSORLESS 1 #endif @@ -2127,7 +2135,7 @@ #ifndef Z_SLAVE_ADDRESS #define Z_SLAVE_ADDRESS 0 #endif - #if NUM_Z_STEPPER_DRIVERS >= 2 + #if NUM_Z_STEPPERS >= 2 #if defined(Z2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2) #define Z2_SENSORLESS 1 #endif @@ -2144,7 +2152,7 @@ #define Z2_SLAVE_ADDRESS 0 #endif #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 #if defined(Z3_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3) #define Z3_SENSORLESS 1 #endif @@ -2161,7 +2169,7 @@ #define Z3_SLAVE_ADDRESS 0 #endif #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) #define Z4_SENSORLESS 1 #endif @@ -2542,8 +2550,8 @@ #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##_) -#define IS_Z3_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && Z3_USE_ENDSTOP == _##A##M##_) -#define IS_Z4_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && Z4_USE_ENDSTOP == _##A##M##_) +#define IS_Z3_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPERS >= 3 && Z3_USE_ENDSTOP == _##A##M##_) +#define IS_Z4_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPERS >= 4 && Z4_USE_ENDSTOP == _##A##M##_) #define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_PROBE_PIN(A,M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_ENDSTOP(A,M) && !IS_Z3_ENDSTOP(A,M) && !IS_Z4_ENDSTOP(A,M)) #if _HAS_STOP(X,MIN) @@ -3420,7 +3428,7 @@ * Advanced Pause - Filament Change */ #if ENABLED(ADVANCED_PAUSE_FEATURE) - #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) #define M600_PURGE_MORE_RESUMABLE 1 #endif #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH @@ -3552,9 +3560,9 @@ * Buzzer/Speaker */ #if PIN_EXISTS(BEEPER) - #define USE_BEEPER 1 + #define HAS_BEEPER 1 #endif -#if USE_BEEPER || ANY(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) +#if ANY(HAS_BEEPER, LCD_USE_I2C_BUZZER, PCA9632_BUZZER) #define HAS_BUZZER 1 #endif diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index 505a0682ebaa..8fdb4b9baeae 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -29,7 +29,6 @@ #ifndef __MARLIN_DEPS__ #include "../HAL/HAL.h" - extern MarlinHAL hal; #endif #include "../pins/pins.h" diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 59effff1a310..4412fbb41e5e 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -371,7 +371,7 @@ #elif defined(FILAMENT_CHANGE_LOAD_LENGTH) #error "FILAMENT_CHANGE_LOAD_LENGTH is now FILAMENT_CHANGE_FAST_LOAD_LENGTH." #elif defined(LEVEL_CORNERS_INSET) - #error "LEVEL_CORNERS_INSET is now LEVEL_CORNERS_INSET_LFRB." + #error "LEVEL_CORNERS_INSET is now BED_TRAMMING_INSET_LFRB." #elif defined(BEZIER_JERK_CONTROL) #error "BEZIER_JERK_CONTROL is now S_CURVE_ACCELERATION." #elif HAS_JUNCTION_DEVIATION && defined(JUNCTION_DEVIATION_FACTOR) @@ -447,6 +447,16 @@ #error "SPINDLE_LASER_ACTIVE_HIGH is now SPINDLE_LASER_ACTIVE_STATE." #elif defined(SPINDLE_LASER_ENABLE_INVERT) #error "SPINDLE_LASER_ENABLE_INVERT is now SPINDLE_LASER_ACTIVE_STATE." +#elif defined(LASER_POWER_INLINE) + #error "LASER_POWER_INLINE is not required, inline mode is enabled with 'M3 I' and disabled with 'M5 I'." +#elif defined(LASER_POWER_INLINE_TRAPEZOID) + #error "LASER_POWER_INLINE_TRAPEZOID is now LASER_POWER_TRAP." +#elif defined(LASER_POWER_INLINE_TRAPEZOID_CONT) + #error "LASER_POWER_INLINE_TRAPEZOID_CONT is replaced with LASER_POWER_TRAP." +#elif defined(LASER_POWER_INLINE_TRAPEZOID_PER) + #error "LASER_POWER_INLINE_TRAPEZOID_CONT_PER replaced with LASER_POWER_TRAP." +#elif defined(LASER_POWER_INLINE_CONTINUOUS) + #error "LASER_POWER_INLINE_CONTINUOUS is not required, inline mode is enabled with 'M3 I' and disabled with 'M5 I'." #elif defined(CUTTER_POWER_DISPLAY) #error "CUTTER_POWER_DISPLAY is now CUTTER_POWER_UNIT." #elif defined(CHAMBER_HEATER_PIN) @@ -524,11 +534,11 @@ #elif defined(Z_QUAD_ENDSTOPS_ADJUSTMENT2) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT3) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT4) #error "Z_QUAD_ENDSTOPS_ADJUSTMENT[234] is now Z[234]_ENDSTOP_ADJUSTMENT." #elif defined(Z_DUAL_STEPPER_DRIVERS) - #error "Z_DUAL_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 2." + #error "Z_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." #elif defined(Z_TRIPLE_STEPPER_DRIVERS) - #error "Z_TRIPLE_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 3." + #error "Z_TRIPLE_STEPPER_DRIVERS is no longer needed and should be removed." #elif defined(Z_QUAD_STEPPER_DRIVERS) - #error "Z_QUAD_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 4." + #error "Z_QUAD_STEPPER_DRIVERS is no longer needed and should be removed." #elif defined(Z_DUAL_ENDSTOPS) || defined(Z_TRIPLE_ENDSTOPS) || defined(Z_QUAD_ENDSTOPS) #error "Z_(DUAL|TRIPLE|QUAD)_ENDSTOPS is now Z_MULTI_ENDSTOPS." #elif defined(DUGS_UI_MOVE_DIS_OPTION) @@ -595,6 +605,8 @@ #error "ARC_SUPPORT no longer uses ARC_SEGMENTS_PER_R." #elif ENABLED(ARC_SUPPORT) && (!defined(MIN_ARC_SEGMENT_MM) || !defined(MAX_ARC_SEGMENT_MM)) #error "ARC_SUPPORT now requires MIN_ARC_SEGMENT_MM and MAX_ARC_SEGMENT_MM." +#elif defined(LASER_POWER_INLINE) + #error "LASER_POWER_INLINE is obsolete." #elif defined(SPINDLE_LASER_PWM) #error "SPINDLE_LASER_PWM (true) is now set with SPINDLE_LASER_USE_PWM (enabled)." #elif ANY(IS_RAMPS_EEB, IS_RAMPS_EEF, IS_RAMPS_EFB, IS_RAMPS_EFF, IS_RAMPS_SF) @@ -621,6 +633,18 @@ #error "DWIN_CREALITY_LCD_ENHANCED is now DWIN_LCD_PROUI." #elif defined(LINEAR_AXES) #error "LINEAR_AXES is now NUM_AXES (to account for rotational axes)." +#elif defined(X_DUAL_STEPPER_DRIVERS) + #error "X_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(Y_DUAL_STEPPER_DRIVERS) + #error "Y_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(NUM_Z_STEPPER_DRIVERS) + #error "NUM_Z_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(LEVEL_BED_CORNERS) + #error "LEVEL_BED_CORNERS is now LCD_BED_TRAMMING." +#elif defined(LEVEL_CORNERS_INSET_LFRB) || defined(LEVEL_CORNERS_HEIGHT) || defined(LEVEL_CORNERS_Z_HOP) || defined(LEVEL_CORNERS_USE_PROBE) || defined(LEVEL_CORNERS_PROBE_TOLERANCE) || defined(LEVEL_CORNERS_VERIFY_RAISED) || defined(LEVEL_CORNERS_AUDIO_FEEDBACK) + #error "LEVEL_CORNERS_* settings have been renamed BED_TRAMMING_*." +#elif defined(LEVEL_CENTER_TOO) + #error "LEVEL_CENTER_TOO is now BED_TRAMMING_INCLUDE_CENTER." #endif constexpr float arm[] = AXIS_RELATIVE_MODES; @@ -737,27 +761,21 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L * Multiple Stepper Drivers Per Axis */ #define GOOD_AXIS_PINS(A) (HAS_##A##_ENABLE && HAS_##A##_STEP && HAS_##A##_DIR) -#if ENABLED(X_DUAL_STEPPER_DRIVERS) - #if ENABLED(DUAL_X_CARRIAGE) - #error "DUAL_X_CARRIAGE is not compatible with X_DUAL_STEPPER_DRIVERS." - #elif !GOOD_AXIS_PINS(X) - #error "X_DUAL_STEPPER_DRIVERS requires X2 pins to be defined." - #endif +#if HAS_X2_STEPPER && !GOOD_AXIS_PINS(X) + #error "If X2_DRIVER_TYPE is defined, then X2 ENABLE/STEP/DIR pins are also needed." #endif -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y) - #error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined." +#if HAS_DUAL_Y_STEPPERS && !GOOD_AXIS_PINS(Y) + #error "If Y2_DRIVER_TYPE is defined, then Y2 ENABLE/STEP/DIR pins are also needed." #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." + #if NUM_Z_STEPPERS >= 2 && !GOOD_AXIS_PINS(Z2) + #error "If Z2_DRIVER_TYPE is defined, then Z2 ENABLE/STEP/DIR pins are also needed." + #elif NUM_Z_STEPPERS >= 3 && !GOOD_AXIS_PINS(Z3) + #error "If Z3_DRIVER_TYPE is defined, then Z3 ENABLE/STEP/DIR pins are also needed." + #elif NUM_Z_STEPPERS >= 4 && !GOOD_AXIS_PINS(Z4) + #error "If Z4_DRIVER_TYPE is defined, then Z4 ENABLE/STEP/DIR pins are also needed." #endif #endif @@ -855,7 +873,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #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, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_*, OR EXTENSIBLE_UI." + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_MARLINUI_*, OR EXTENSIBLE_UI." #endif #if ENABLED(USE_M73_REMAINING_TIME) && DISABLED(LCD_SET_PROGRESS_MANUALLY) @@ -887,9 +905,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * SD Card Settings */ -#if ALL(SDSUPPORT, ELB_FULL_GRAPHIC_CONTROLLER, HAS_MARLINUI_MENU) && PIN_EXISTS(SD_DETECT) && SD_DETECT_STATE != HIGH && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) +#if ALL(SDSUPPORT, HAS_SD_DETECT, SD_CONNECTION_TYPICAL, ELB_FULL_GRAPHIC_CONTROLLER, HAS_MARLINUI_MENU) && SD_DETECT_STATE == LOW #error "SD_DETECT_STATE must be set HIGH for SD on the ELB_FULL_GRAPHIC_CONTROLLER." #endif +#undef SD_CONNECTION_TYPICAL /** * SD File Sorting @@ -1560,8 +1579,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Allow only one kinematic type to be defined */ -#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, FOAMCUTTER_XYUV) - #error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, or FOAMCUTTER_XYUV." +#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, ARTICULATED_ROBOT_ARM, FOAMCUTTER_XYUV) + #error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, ARTICULATED_ROBOT_ARM, or FOAMCUTTER_XYUV." #endif /** @@ -1608,8 +1627,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS */ #if 1 < 0 \ + (DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE) \ - + COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4) - #error "Please enable only one probe option: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, MAGLEV4, or Z Servo." + + COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4, MAG_MOUNTED_PROBE) + #error "Please enable only one probe option: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, MAGLEV4, MAG_MOUNTED_PROBE or Z Servo." #endif #if HAS_BED_PROBE @@ -1715,13 +1734,20 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif + /** + * Mag mounted probe requirements + */ + #if BOTH(MAG_MOUNTED_PROBE, USE_PROBE_FOR_Z_HOMING) && DISABLED(Z_SAFE_HOMING) + #error "MAG_MOUNTED_PROBE requires Z_SAFE_HOMING if it's being used to home Z." + #endif + /** * MagLev V4 probe requirements */ #if ENABLED(MAGLEV4) #if !PIN_EXISTS(MAGLEV_TRIGGER) #error "MAGLEV4 requires MAGLEV_TRIGGER_PIN to be defined." - #elif DISABLED(Z_SAFE_HOMING) + #elif ENABLED(HOMING_Z_WITH_PROBE) && DISABLED(Z_SAFE_HOMING) #error "MAGLEV4 requires Z_SAFE_HOMING." #elif MAGLEV_TRIGGER_DELAY != 15 #error "MAGLEV_TRIGGER_DELAY should not be changed. Comment out this line to continue." @@ -1824,14 +1850,14 @@ 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 ENABLED(LCD_BED_TRAMMING) + #ifndef BED_TRAMMING_INSET_LFRB + #error "LCD_BED_TRAMMING requires BED_TRAMMING_INSET_LFRB values." + #elif ENABLED(BED_TRAMMING_USE_PROBE) #if !HAS_BED_PROBE - #error "LEVEL_CORNERS_USE_PROBE requires a real probe." + #error "BED_TRAMMING_USE_PROBE requires a real probe." #elif ENABLED(SENSORLESS_PROBING) - #error "LEVEL_CORNERS_USE_PROBE is incompatible with SENSORLESS_PROBING." + #error "BED_TRAMMING_USE_PROBE is incompatible with SENSORLESS_PROBING." #endif #endif #endif @@ -1917,7 +1943,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * LCD_BED_LEVELING requirements */ #if ENABLED(LCD_BED_LEVELING) - #if NONE(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI) + #if !HAS_MARLINUI_MENU #error "LCD_BED_LEVELING is not supported by the selected LCD controller." #elif !(ENABLED(MESH_BED_LEVELING) || HAS_ABL_NOT_UBL) #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or AUTO_BED_LEVELING." @@ -2374,18 +2400,6 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #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 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 @@ -2394,8 +2408,6 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if TEMP_SENSOR_BOARD #if !PIN_EXISTS(TEMP_BOARD) #error "TEMP_SENSOR_BOARD requires TEMP_BOARD_PIN." - #elif !HAS_TEMP_ADC_BOARD - #error "TEMP_BOARD_PIN must be an ADC pin." #elif ENABLED(THERMAL_PROTECTION_BOARD) && (!defined(BOARD_MINTEMP) || !defined(BOARD_MAXTEMP)) #error "THERMAL_PROTECTION_BOARD requires BOARD_MINTEMP and BOARD_MAXTEMP." #endif @@ -2443,23 +2455,23 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif /** - * FYSETC LCD Requirements + * FYSETC/MKS/BTT Mini Panel Requirements */ #if EITHER(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) - #ifndef NEO_GRB - #define NEO_GRB 123 + #ifndef NEO_RGB + #define NEO_RGB 123 #define FAUX_RGB 1 #endif - #if defined(NEOPIXEL_TYPE) && NEOPIXEL_TYPE != NEO_GRB - #error "Your FYSETC Mini Panel requires NEOPIXEL_TYPE to be NEO_GRB." + #if defined(NEOPIXEL_TYPE) && NEOPIXEL_TYPE != NEO_RGB + #error "Your FYSETC/MKS/BTT Mini Panel requires NEOPIXEL_TYPE to be NEO_RGB." #elif defined(NEOPIXEL_PIXELS) && NEOPIXEL_PIXELS < 3 - #error "Your FYSETC Mini Panel requires NEOPIXEL_PIXELS >= 3." + #error "Your FYSETC/MKS/BTT Mini Panel requires NEOPIXEL_PIXELS >= 3." #endif #if FAUX_RGB - #undef NEO_GRB + #undef NEO_RGB #undef FAUX_RGB #endif -#elif EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && !DISABLED(RGB_LED) +#elif EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) #error "Your FYSETC Mini Panel requires RGB_LED." #endif @@ -2639,10 +2651,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Z_MULTI_ENDSTOPS is not compatible with DELTA." #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." + #elif !Z3_USE_ENDSTOP && NUM_Z_STEPPERS >= 3 + #error "Z3_USE_ENDSTOP must be set with Z_MULTI_ENDSTOPS and Z3_DRIVER_TYPE." + #elif !Z4_USE_ENDSTOP && NUM_Z_STEPPERS >= 4 + #error "Z4_USE_ENDSTOP must be set with Z_MULTI_ENDSTOPS and Z4_DRIVER_TYPE." #endif #endif @@ -2841,7 +2853,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + 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, DGUS_LCD_UI_RELOADED) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY) \ - + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ + COUNT_ENABLED(MKS_12864OLED, MKS_12864OLED_SSD1306) \ @@ -2930,8 +2942,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 4) - #error "GRAPHICAL_TFT_UPSCALE must be 2, 3, or 4." +#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 6) + #error "GRAPHICAL_TFT_UPSCALE must be between 2 and 6." #endif #if BOTH(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) @@ -2966,8 +2978,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "DWIN_CREALITY_LCD does not support PID_EDIT_MENU or PID_AUTOTUNE_MENU." #elif EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) #error "DWIN_CREALITY_LCD does not support MPC_EDIT_MENU or MPC_AUTOTUNE_MENU." - #elif ENABLED(LEVEL_BED_CORNERS) - #error "DWIN_CREALITY_LCD does not support LEVEL_BED_CORNERS." + #elif ENABLED(LCD_BED_TRAMMING) + #error "DWIN_CREALITY_LCD does not support LCD_BED_TRAMMING." #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) #error "DWIN_CREALITY_LCD does not support LCD_BED_LEVELING with PROBE_MANUALLY." #endif @@ -2978,8 +2990,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "DWIN_LCD_PROUI does not support PID_EDIT_MENU or PID_AUTOTUNE_MENU." #elif EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) #error "DWIN_LCD_PROUI does not support MPC_EDIT_MENU or MPC_AUTOTUNE_MENU." - #elif ENABLED(LEVEL_BED_CORNERS) - #error "DWIN_LCD_PROUI does not support LEVEL_BED_CORNERS." + #elif ENABLED(LCD_BED_TRAMMING) + #error "DWIN_LCD_PROUI does not support LCD_BED_TRAMMING." #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) #error "DWIN_LCD_PROUI does not support LCD_BED_LEVELING with PROBE_MANUALLY." #endif @@ -3049,6 +3061,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #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." + #elif ENABLED(NEXTION_LCD) + #error "NEXTION_LCD requires LCD_SERIAL_PORT to be defined." #endif #endif @@ -3703,14 +3717,14 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #endif #if ENABLED(Z_STEPPER_AUTO_ALIGN) - #if NUM_Z_STEPPER_DRIVERS <= 1 - #error "Z_STEPPER_AUTO_ALIGN requires NUM_Z_STEPPER_DRIVERS greater than 1." + #if NUM_Z_STEPPERS <= 1 + #error "Z_STEPPER_AUTO_ALIGN requires more than one Z stepper." #elif !HAS_BED_PROBE #error "Z_STEPPER_AUTO_ALIGN requires a Z-bed probe." #elif HAS_Z_STEPPER_ALIGN_STEPPER_XY 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_STEPPER_XY requires NUM_Z_STEPPER_DRIVERS to be 3 or 4." + #if NUM_Z_STEPPERS < 3 + #error "Z_STEPPER_ALIGN_STEPPER_XY requires 3 or 4 Z steppers." #endif #endif #endif @@ -3846,39 +3860,29 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "CUTTER_POWER_UNIT must be PWM255, PERCENT, RPM, or SERVO." #endif - #if ENABLED(LASER_POWER_INLINE) + #if ENABLED(LASER_FEATURE) #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." + #error "SPINDLE_CHANGE_DIR and LASER_FEATURE are incompatible." + #elif ENABLED(LASER_MOVE_G0_OFF) + #error "LASER_MOVE_G0_OFF is no longer required, G0 and G28 cannot apply power." + #elif ENABLED(LASER_MOVE_G28_OFF) + #error "LASER_MOVE_G0_OFF is no longer required, G0 and G28 cannot apply power." + #elif ENABLED(LASER_MOVE_POWER) + #error "LASER_MOVE_POWER is no longer applicable." #endif - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + #if ENABLED(LASER_POWER_TRAP) #if DISABLED(SPINDLE_LASER_USE_PWM) - #error "LASER_POWER_INLINE_TRAPEZOID requires SPINDLE_LASER_USE_PWM to function." - #elif ENABLED(S_CURVE_ACCELERATION) - //#ifndef LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN - // #define LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN - // #warning "Combining LASER_POWER_INLINE_TRAPEZOID with S_CURVE_ACCELERATION may result in unintended behavior." - //#endif + #error "LASER_POWER_TRAP requires SPINDLE_LASER_USE_PWM to function." #endif #endif - #if ENABLED(LASER_POWER_INLINE_INVERT) - //#ifndef LASER_POWER_INLINE_INVERT_WARN - // #define LASER_POWER_INLINE_INVERT_WARN - // #warning "Enabling LASER_POWER_INLINE_INVERT means that `M5` won't kill the laser immediately; use `M5 I` instead." - //#endif - #endif #else #if SPINDLE_LASER_POWERUP_DELAY < 1 #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0." #elif SPINDLE_LASER_POWERDOWN_DELAY < 1 #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0." - #elif ENABLED(LASER_MOVE_POWER) - #error "LASER_MOVE_POWER requires LASER_POWER_INLINE." - #elif ANY(LASER_POWER_INLINE_TRAPEZOID, LASER_POWER_INLINE_INVERT, LASER_MOVE_G0_OFF, LASER_MOVE_POWER) - #error "Enabled an inline laser feature without inline laser power being enabled." #endif #endif + #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." @@ -3893,7 +3897,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "SPINDLE_LASER_PWM_PIN not assigned to a PWM pin." #elif !defined(SPINDLE_LASER_PWM_INVERT) #error "SPINDLE_LASER_PWM_INVERT is required for (SPINDLE|LASER)_FEATURE." - #elif !(defined(SPEED_POWER_INTERCEPT) && defined(SPEED_POWER_MIN) && defined(SPEED_POWER_MAX) && defined(SPEED_POWER_STARTUP)) + #elif !(defined(SPEED_POWER_MIN) && defined(SPEED_POWER_MAX) && defined(SPEED_POWER_STARTUP)) #error "SPINDLE_LASER_USE_PWM equation constant(s) missing." #elif _PIN_CONFLICT(X_MIN) #error "SPINDLE_LASER_USE_PWM pin conflicts with X_MIN_PIN." @@ -3946,6 +3950,11 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #endif #endif #undef _PIN_CONFLICT + + #ifdef LASER_SAFETY_TIMEOUT_MS + static_assert(LASER_SAFETY_TIMEOUT_MS < (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL, "LASER_SAFETY_TIMEOUT_MS must be less than DEFAULT_STEPPER_DEACTIVE_TIME (" STRINGIFY(DEFAULT_STEPPER_DEACTIVE_TIME) " seconds)"); + #endif + #endif #if ENABLED(COOLANT_MIST) && !PIN_EXISTS(COOLANT_MIST) @@ -4127,8 +4136,8 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "DGUS_LCD_UI_RELOADED requires a bed probe." #elif !HAS_MESH #error "DGUS_LCD_UI_RELOADED requires mesh leveling." - #elif DISABLED(LEVEL_BED_CORNERS) - #error "DGUS_LCD_UI_RELOADED requires LEVEL_BED_CORNERS." + #elif DISABLED(LCD_BED_TRAMMING) + #error "DGUS_LCD_UI_RELOADED requires LCD_BED_TRAMMING." #elif DISABLED(BABYSTEP_ALWAYS_AVAILABLE) #error "DGUS_LCD_UI_RELOADED requires BABYSTEP_ALWAYS_AVAILABLE." #elif DISABLED(BABYSTEP_ZPROBE_OFFSET) @@ -4149,3 +4158,8 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE) #error "DISABLE_JTAG is not supported for the selected MCU/Board." #endif + +// Check requirements for upload.py +#if ENABLED(XFER_BUILD) && !BOTH(BINARY_FILE_TRANSFER, CUSTOM_FIRMWARE_UPLOAD) + #error "BINARY_FILE_TRANSFER and CUSTOM_FIRMWARE_UPLOAD are required for custom upload." +#endif diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6e3be7545df0..14152da26bef 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 "bugfix-2.0.x" + #define SHORT_BUILD_VERSION "bugfix-2.1.x" #endif /** @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-04-24" + #define STRING_DISTRIBUTION_DATE "2022-07-07" #endif /** @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 02010000 +#define MARLIN_HEX_VERSION 02010100 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 96f8dc7d54b2..054a006aff26 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -35,6 +35,10 @@ #warning "WARNING! Disable MARLIN_DEV_MODE for the final build!" #endif +#if NUM_AXES_WARNING + #warning "Note: NUM_AXES is now based on the *_DRIVER_TYPE settings so you can remove NUM_AXES from Configuration.h." +#endif + // Safety Features #if DISABLED(USE_WATCHDOG) #warning "Safety Alert! Enable USE_WATCHDOG for the final build!" @@ -67,6 +71,10 @@ #ifndef NO_AUTO_ASSIGN_WARNING + #if AUTO_ASSIGNED_LCD_SERIAL + #warning "Note: Auto-assigned LCD_SERIAL_PORT. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)" + #endif + #if AUTO_ASSIGNED_X2_STEPPER #warning "Note: Auto-assigned X2 STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)" #endif @@ -736,10 +744,10 @@ #endif /** - * FYSETC backlighting + * FYSETC/MKS/BTT Mini Panel backlighting */ #if EITHER(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) && !ALL(NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, LED_COLOR_PRESETS) - #warning "Your FYSETC Mini Panel works best with NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, and LED_COLOR_PRESETS." + #warning "Your FYSETC/MKS/BTT Mini Panel works best with NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, and LED_COLOR_PRESETS." #endif #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) @@ -753,7 +761,7 @@ #endif /** - * Maple environent + * Maple environment */ #ifdef __STM32F1__ #warning "Maple build environments are deprecated. Please use a non-Maple build environment. Report issues to the Marlin Firmware project." diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp index 31b26aa5bbcb..fe31c21e3959 100644 --- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp +++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp @@ -50,7 +50,7 @@ extern LCD_CLASS lcd; int lcd_glyph_height() { return 1; } typedef struct _hd44780_charmap_t { - wchar_t uchar; // the unicode char + lchar_t uchar; // the unicode char uint8_t idx; // the glyph of the char in the ROM uint8_t idx2; // the char used to be combined with the idx to simulate a single char } hd44780_charmap_t; @@ -992,7 +992,7 @@ void lcd_put_int(const int i) { lcd.print(i); } // return < 0 on error // return the advanced cols -int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { +int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { // find the HD44780 internal ROM first int ret; @@ -1047,23 +1047,23 @@ int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { * * Draw a UTF-8 string */ -static int lcd_put_u8str_max_cb(const char * utf8_str, uint8_t (*cb_read_byte)(uint8_t * str), pixel_len_t max_length) { +static int lcd_put_u8str_max_cb(const char * utf8_str, read_byte_cb_t cb_read_byte, const pixel_len_t max_length) { pixel_len_t ret = 0; - uint8_t *p = (uint8_t *)utf8_str; + const uint8_t *p = (uint8_t *)utf8_str; while (ret < max_length) { - wchar_t ch = 0; - p = get_utf8_value_cb(p, cb_read_byte, &ch); - if (!ch) break; - ret += lcd_put_wchar_max(ch, max_length - ret); + lchar_t wc; + p = get_utf8_value_cb(p, cb_read_byte, wc); + if (!wc) break; + ret += lcd_put_lchar_max(wc, max_length - ret); } return (int)ret; } -int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { +int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); } -int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P utf8_pstr, const pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_pstr, read_byte_rom, max_length); } diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index db4bd4e19e8c..d8306dbf945d 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -121,7 +121,7 @@ static void createChar_P(const char c, const byte * const ptr) { #if ENABLED(LCD_USE_I2C_BUZZER) void MarlinUI::buzz(const long duration, const uint16_t freq) { - if (!buzzer_enabled) return; + if (!sound_on) return; lcd.buzz(duration, freq); } #endif @@ -405,15 +405,15 @@ void MarlinUI::clear_lcd() { lcd.clear(); } void lcd_erase_line(const lcd_uint_t line) { lcd_moveto(0, line); for (uint8_t i = LCD_WIDTH + 1; --i;) - lcd_put_wchar(' '); + lcd_put_lchar(' '); } // 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, FSTR_P const ftxt, const uint8_t len, const int16_t time) { - uint8_t slen = utf8_strlen_P(FTOP(ftxt)); + uint8_t slen = utf8_strlen(ftxt); if (slen < len) { lcd_put_u8str_max(col, line, ftxt, len); - for (; slen < len; ++slen) lcd_put_wchar(' '); + for (; slen < len; ++slen) lcd_put_lchar(' '); safe_delay(time); } else { @@ -425,7 +425,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); } lcd_put_u8str_max_P(col, line, p, len); // Fill with spaces - for (uint8_t ix = slen - i; ix < len; ++ix) lcd_put_wchar(' '); + for (uint8_t ix = slen - i; ix < len; ++ix) lcd_put_lchar(' '); // Delay safe_delay(dly); @@ -437,11 +437,11 @@ void MarlinUI::clear_lcd() { lcd.clear(); } } } - 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(F( "------" )); lcd_put_wchar('\x01'); - lcd_put_u8str(indent, 1, F("|Marlin|")); lcd_put_u8str_P(extra); - lcd_put_wchar(indent, 2, '\x02'); lcd_put_u8str(F( "------" )); lcd_put_wchar('\x03'); + static void logo_lines(FSTR_P const extra) { + int16_t indent = (LCD_WIDTH - 8 - utf8_strlen(extra)) / 2; + lcd_put_lchar(indent, 0, '\x00'); lcd_put_u8str(F( "------" )); lcd_put_lchar('\x01'); + lcd_put_u8str(indent, 1, F("|Marlin|")); lcd_put_u8str(extra); + lcd_put_lchar(indent, 2, '\x02'); lcd_put_u8str(F( "------" )); lcd_put_lchar('\x03'); } void MarlinUI::show_bootscreen() { @@ -468,7 +468,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); } // // Show the Marlin logo, splash line1, and splash line 2 // - logo_lines(PSTR(" " SHORT_BUILD_VERSION)); + logo_lines(F(" " SHORT_BUILD_VERSION)); CENTER_OR_SCROLL(MARLIN_WEBSITE_URL, 2000); } else { @@ -476,7 +476,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); } // Show the Marlin logo and short build version // After a delay show the website URL // - logo_lines(NUL_STR); + logo_lines(FPSTR(NUL_STR)); CENTER_OR_SCROLL(SHORT_BUILD_VERSION, 1500); CENTER_OR_SCROLL(MARLIN_WEBSITE_URL, 1500); #ifdef STRING_SPLASH_LINE3 @@ -495,12 +495,13 @@ void MarlinUI::clear_lcd() { lcd.clear(); } #endif // SHOW_BOOTSCREEN void MarlinUI::draw_kill_screen() { - lcd_put_u8str(0, 0, status_message); - lcd_uint_t y = 2; + lcd_uint_t x = 0, y = 0; + lcd_put_u8str(x, y, status_message); + y = 2; #if LCD_HEIGHT >= 4 - lcd_put_u8str(0, y++, GET_TEXT_F(MSG_HALTED)); + lcd_put_u8str(x, y++, GET_TEXT_F(MSG_HALTED)); #endif - lcd_put_u8str(0, y, GET_TEXT_F(MSG_PLEASE_RESET)); + lcd_put_u8str(x, y, GET_TEXT_F(MSG_PLEASE_RESET)); } // @@ -509,11 +510,11 @@ void MarlinUI::draw_kill_screen() { // 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)); + lcd_put_lchar('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 : '?'); + while (const char c = *value++) lcd_put_lchar(c <= '.' ? c : '?'); else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) lcd_put_u8str(axis == Z_AXIS ? F(" ") : F(" ")); else @@ -530,27 +531,27 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char pr const celsius_t t1 = thermalManager.wholeDegHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id); #endif - if (prefix >= 0) lcd_put_wchar(prefix); + if (prefix >= 0) lcd_put_lchar(prefix); lcd_put_u8str(t1 < 0 ? "err" : i16tostr3rj(t1)); - lcd_put_wchar('/'); + lcd_put_lchar('/'); #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(' '); + lcd_put_lchar(' '); + if (t2 >= 10) lcd_put_lchar(' '); + if (t2 >= 100) lcd_put_lchar(' '); } 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(' '); + lcd_put_lchar(LCD_STR_DEGREE[0]); + lcd_put_lchar(' '); + if (t2 < 10) lcd_put_lchar(' '); } } @@ -558,27 +559,27 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char pr 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); + if (prefix >= 0) lcd_put_lchar(prefix); lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegCooler())); - lcd_put_wchar('/'); + lcd_put_lchar('/'); #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(' '); + lcd_put_lchar(' '); + if (t2 >= 10) lcd_put_lchar(' '); + if (t2 >= 100) lcd_put_lchar(' '); } 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(' '); + lcd_put_lchar(LCD_STR_DEGREE[0]); + lcd_put_lchar(' '); + if (t2 < 10) lcd_put_lchar(' '); } } #endif @@ -587,7 +588,7 @@ FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) { FORCE_INLINE void _draw_flowmeter_status() { lcd_put_u8str("~"); lcd_put_u8str(ftostr11ns(cooler.flowrate)); - lcd_put_wchar('L'); + lcd_put_lchar('L'); } #endif @@ -601,7 +602,7 @@ FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) { } else { lcd_put_u8str(ftostr12ns(ammeter.current)); - lcd_put_wchar('A'); + lcd_put_lchar('A'); } } #endif @@ -619,7 +620,7 @@ FORCE_INLINE void _draw_bed_status(const bool blink) { lcd_put_u8str(ui8tostr3rj(progress)); else lcd_put_u8str(F("---")); - lcd_put_wchar('%'); + lcd_put_lchar('%'); } #endif @@ -666,7 +667,7 @@ void MarlinUI::draw_status_message(const bool blink) { lcd_put_u8str(ftostr12ns(filwidth.measured_mm)); lcd_put_u8str(F(" V")); lcd_put_u8str(i16tostr3rj(planner.volumetric_percent(parser.volumetric_enabled))); - lcd_put_wchar('%'); + lcd_put_lchar('%'); return; } @@ -685,7 +686,7 @@ void MarlinUI::draw_status_message(const bool blink) { lcd_put_u8str(status_message); // Fill the rest with spaces - while (slen < LCD_WIDTH) { lcd_put_wchar(' '); ++slen; } + while (slen < LCD_WIDTH) { lcd_put_lchar(' '); ++slen; } } else { // String is larger than the available space in screen. @@ -699,11 +700,11 @@ void MarlinUI::draw_status_message(const bool blink) { // 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 + lcd_put_lchar(' '); // Always at 1+ spaces left, draw a space if (--chars) { // Draw a second space if there's room - lcd_put_wchar(' '); + lcd_put_lchar(' '); if (--chars) { // Draw a third space if there's room - lcd_put_wchar(' '); + lcd_put_lchar(' '); if (--chars) lcd_put_u8str_max(status_message, chars); // Print a second copy of the message } @@ -725,7 +726,7 @@ void MarlinUI::draw_status_message(const bool blink) { // Fill the rest with spaces if there are missing spaces while (slen < LCD_WIDTH) { - lcd_put_wchar(' '); + lcd_put_lchar(' '); ++slen; } #endif @@ -777,7 +778,7 @@ inline uint8_t draw_elapsed_or_remaining_time(uint8_t timepos, const bool blink) duration_t remaining = (progress > 0) ? ((elapsed * 25600 / progress) >> 8) - elapsed : 0; #endif timepos -= remaining.toDigital(buffer); - lcd_put_wchar(timepos, 2, 'R'); + lcd_put_lchar(timepos, 2, 'R'); } #else constexpr bool show_remain = false; @@ -786,7 +787,7 @@ inline uint8_t draw_elapsed_or_remaining_time(uint8_t timepos, const bool blink) 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_lchar(timepos, 2, LCD_STR_CLOCK[0]); } lcd_put_u8str(buffer); return timepos; @@ -911,7 +912,7 @@ void MarlinUI::draw_status_screen() { else { const xy_pos_t lpos = current_position.asLogical(); _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); - lcd_put_wchar(' '); + lcd_put_lchar(' '); _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); } @@ -925,7 +926,7 @@ void MarlinUI::draw_status_screen() { _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 ? '_' : ' '); + lcd_put_lchar(planner.leveling_active || blink ? '_' : ' '); #endif #endif // LCD_HEIGHT > 2 @@ -934,9 +935,9 @@ void MarlinUI::draw_status_screen() { #if LCD_HEIGHT > 3 - lcd_put_wchar(0, 2, LCD_STR_FEEDRATE[0]); + lcd_put_lchar(0, 2, LCD_STR_FEEDRATE[0]); lcd_put_u8str(i16tostr3rj(feedrate_percentage)); - lcd_put_wchar('%'); + lcd_put_lchar('%'); const uint8_t timepos = draw_elapsed_or_remaining_time(LCD_WIDTH - 1, blink); @@ -968,9 +969,9 @@ void MarlinUI::draw_status_screen() { per = planner.flow_percentage[0]; #endif } - lcd_put_wchar(c); + lcd_put_lchar(c); lcd_put_u8str(i16tostr3rj(per)); - lcd_put_wchar('%'); + lcd_put_lchar('%'); #endif #endif @@ -992,7 +993,7 @@ void MarlinUI::draw_status_screen() { _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 ? '_' : ' '); + lcd_put_lchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' '); #endif // ========== Line 2 ========== @@ -1007,9 +1008,9 @@ void MarlinUI::draw_status_screen() { _draw_bed_status(blink); #endif - lcd_put_wchar(LCD_WIDTH - 9, 1, LCD_STR_FEEDRATE[0]); + lcd_put_lchar(LCD_WIDTH - 9, 1, LCD_STR_FEEDRATE[0]); lcd_put_u8str(i16tostr3rj(feedrate_percentage)); - lcd_put_wchar('%'); + lcd_put_lchar('%'); // ========== Line 3 ========== @@ -1067,74 +1068,74 @@ void MarlinUI::draw_status_screen() { #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*/) { + void MenuItem_static::draw(const uint8_t row, FSTR_P const fstr, 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, + const int8_t plen = fstr ? utf8_strlen(fstr) : 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--; } + while (--pad >= 0) { lcd_put_lchar(' '); n--; } } - if (plen) n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n); + if (plen) n = lcd_put_u8str(fstr, itemIndex, itemStringC, itemStringF, n); if (vlen) n -= lcd_put_u8str_max(vstr, n); - for (; n > 0; --n) lcd_put_wchar(' '); + for (; n > 0; --n) lcd_put_lchar(' '); } // 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); + void MenuItemBase::_draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char pre_char, const char post_char) { + lcd_put_lchar(0, row, sel ? pre_char : ' '); + uint8_t n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 2); + for (; n; --n) lcd_put_lchar(' '); + lcd_put_lchar(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) { + void MenuEditItemBase::draw(const bool sel, const uint8_t row, FSTR_P const ftpl, 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); + lcd_put_lchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' '); + uint8_t n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 2 - vlen); if (vlen) { - lcd_put_wchar(':'); - for (; n; --n) lcd_put_wchar(' '); + lcd_put_lchar(':'); + for (; n; --n) lcd_put_lchar(' '); 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*/) { + void MenuEditItemBase::draw_edit_screen(FSTR_P const ftpl, 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); + uint8_t n = lcd_put_u8str(0, 1, ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 1); if (value) { - lcd_put_wchar(':'); n--; + lcd_put_lchar(':'); 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_lchar(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*/) { + void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, const bool yesno, FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/) { ui.draw_select_screen_prompt(pref, string, suff); if (no) { SETCURSOR(0, LCD_HEIGHT - 1); - lcd_put_wchar(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd_put_wchar(yesno ? ' ' : ']'); + lcd_put_lchar(yesno ? ' ' : '['); lcd_put_u8str(no); lcd_put_lchar(yesno ? ' ' : ']'); } if (yes) { - SETCURSOR_RJ(utf8_strlen_P(yes) + 2, LCD_HEIGHT - 1); - lcd_put_wchar(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd_put_wchar(yesno ? ']' : ' '); + SETCURSOR_RJ(utf8_strlen(yes) + 2, LCD_HEIGHT - 1); + lcd_put_lchar(yesno ? '[' : ' '); lcd_put_u8str(yes); lcd_put_lchar(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] : ' '); + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { + lcd_put_lchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' '); 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] : ' '); + for (; n; --n) lcd_put_lchar(' '); + lcd_put_lchar(isDir ? LCD_STR_FOLDER[0] : ' '); } #endif @@ -1252,7 +1253,7 @@ void MarlinUI::draw_status_screen() { 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); + lcd_put_lchar(x, y, c); } void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { @@ -1269,7 +1270,7 @@ void MarlinUI::draw_status_screen() { #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 _LABEL(X,Y,C) lcd_put_lchar(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) @@ -1281,9 +1282,9 @@ void MarlinUI::draw_status_screen() { * Show X and Y positions */ _XLABEL(_PLOT_X, 0); - lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(ubl.mesh_index_to_xpos(x_plot)))); + lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(bedlevel.get_mesh_x(x_plot)))); _YLABEL(_LCD_W_POS, 0); - lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(ubl.mesh_index_to_ypos(y_plot)))); + lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(bedlevel.get_mesh_y(y_plot)))); lcd_moveto(_PLOT_X, 0); @@ -1332,13 +1333,13 @@ void MarlinUI::draw_status_screen() { 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 + lcd_put_lchar(i, 0, CHAR_LINE_TOP); // Box Top line + lcd_put_lchar(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 + lcd_put_lchar(0, j, CHAR_EDGE_L); // Box Left edge + lcd_put_lchar(n_cols - 1, j, CHAR_EDGE_R); // Box Right edge } /** @@ -1348,8 +1349,8 @@ void MarlinUI::draw_status_screen() { 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 + lcd_put_lchar(0, n_rows - 1, ' '); // Box Left edge + lcd_put_lchar(n_cols - 1, n_rows - 1, ' '); // Box Right edge } clear_custom_char(&new_char); @@ -1463,11 +1464,11 @@ void MarlinUI::draw_status_screen() { /** * Print plot position */ - lcd_put_wchar(_LCD_W_POS, 0, '('); + lcd_put_lchar(_LCD_W_POS, 0, '('); lcd_put_u8str(ui8tostr3rj(x_plot)); - lcd_put_wchar(','); + lcd_put_lchar(','); lcd_put_u8str(ui8tostr3rj(y_plot)); - lcd_put_wchar(')'); + lcd_put_lchar(')'); #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display @@ -1475,8 +1476,8 @@ void MarlinUI::draw_status_screen() { * 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])); + if (!isnan(bedlevel.z_values[x_plot][y_plot])) + lcd_put_u8str(ftostr43sign(bedlevel.z_values[x_plot][y_plot])); else lcd_put_u8str(F(" -----")); @@ -1486,16 +1487,16 @@ void MarlinUI::draw_status_screen() { * 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)))); + lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(bedlevel.get_mesh_x(x_plot)))); _YLABEL(_LCD_W_POS, 2); - lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(ubl.mesh_index_to_ypos(y_plot)))); + lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(bedlevel.get_mesh_y(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])); + if (!isnan(bedlevel.z_values[x_plot][y_plot])) + lcd_put_u8str(ftostr43sign(bedlevel.z_values[x_plot][y_plot])); else lcd_put_u8str(F(" -----")); diff --git a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp index d0cf5795d235..e681ff0a9170 100644 --- a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp @@ -48,7 +48,7 @@ int lcd_glyph_height() { return 1; } typedef struct _TFTGLCD_charmap_t { - wchar_t uchar; // the unicode char + lchar_t uchar; // the unicode char uint8_t idx; // the glyph of the char in the ROM uint8_t idx2; // the char used to be combined with the idx to simulate a single char } TFTGLCD_charmap_t; @@ -991,7 +991,7 @@ void lcd_put_int(const int i) { // return < 0 on error // return the advanced cols -int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { +int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { // find the HD44780 internal ROM first int ret; @@ -1045,23 +1045,23 @@ int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { * * Draw a UTF-8 string */ -static int lcd_put_u8str_max_cb(const char * utf8_str, uint8_t (*cb_read_byte)(uint8_t * str), pixel_len_t max_length) { +static int lcd_put_u8str_max_cb(const char * utf8_str, read_byte_cb_t cb_read_byte, const pixel_len_t max_length) { pixel_len_t ret = 0; - uint8_t *p = (uint8_t *)utf8_str; + const uint8_t *p = (uint8_t *)utf8_str; while (ret < max_length) { - wchar_t ch = 0; - p = get_utf8_value_cb(p, cb_read_byte, &ch); - if (!ch) break; - ret += lcd_put_wchar_max(ch, max_length - ret); + lchar_t wc; + p = get_utf8_value_cb(p, cb_read_byte, wc); + if (!wc) break; + ret += lcd_put_lchar_max(wc, max_length - ret); } return (int)ret; } -int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { +int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); } -int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P utf8_pstr, const pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_pstr, read_byte_rom, max_length); } diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index 0745397f4f99..f3d98ec55584 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -301,7 +301,7 @@ uint8_t MarlinUI::read_slow_buttons() { // Duration in ms, freq in Hz void MarlinUI::buzz(const long duration, const uint16_t freq) { if (!PanelDetected) return; - if (!buzzer_enabled) return; + if (!sound_on) return; #if ENABLED(TFTGLCD_PANEL_SPI) WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(BUZZER); @@ -380,13 +380,14 @@ void MarlinUI::clear_lcd() { void MarlinUI::_set_contrast() { lcd.setContrast(contrast); } #endif -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 !IS_TFTGLCD_PANEL + void lcd_moveto(const uint8_t col, const uint8_t row) { lcd.setCursor(col, row); } +#endif + +static void center_text(FSTR_P const fstart, const uint8_t y) { + const uint8_t len = utf8_strlen(fstart); + lcd_moveto(len < LCD_WIDTH ? (LCD_WIDTH - len) / 2 : 0, y); + lcd_put_u8str(fstart); } #if ENABLED(SHOW_BOOTSCREEN) @@ -399,11 +400,11 @@ static void center_text_P(PGM_P pstart, uint8_t y) { 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(F("------")); lcd.write(TRC); - lcd.setCursor(indent, 1); lcd.write(LR); lcd_put_u8str(F("Marlin")); lcd.write(LR); - lcd.setCursor(indent, 2); lcd.write(BLC); lcd_put_u8str(F("------")); lcd.write(BRC); - center_text_P(PSTR(SHORT_BUILD_VERSION), 3); - center_text_P(PSTR(MARLIN_WEBSITE_URL), 4); + lcd_moveto(indent, 0); lcd.write(TLC); lcd_put_u8str(F("------")); lcd.write(TRC); + lcd_moveto(indent, 1); lcd.write(LR); lcd_put_u8str(F("Marlin")); lcd.write(LR); + lcd_moveto(indent, 2); lcd.write(BLC); lcd_put_u8str(F("------")); lcd.write(BRC); + center_text(F(SHORT_BUILD_VERSION), 3); + center_text(F(MARLIN_WEBSITE_URL), 4); picBits = ICON_LOGO; lcd.print_screen(); } @@ -417,11 +418,11 @@ static void center_text_P(PGM_P pstart, uint8_t y) { 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_moveto(0, 3); lcd.write(COLOR_ERROR); + lcd_moveto((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); + center_text(GET_TEXT_F(MSG_HALTED), 5); + center_text(GET_TEXT_F(MSG_PLEASE_RESET), 6); lcd.print_screen(); } @@ -456,25 +457,25 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #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); + lcd_moveto(2, 5); lcd.print(prefix); //HE + lcd_moveto(1, 6); lcd.print(i16tostr3rj(t1)); + lcd_moveto(1, 7); } else { - lcd.setCursor(6, 5); lcd.print(prefix); //BED - lcd.setCursor(6, 6); lcd.print(i16tostr3rj(t1)); - lcd.setCursor(6, 7); + lcd_moveto(6, 5); lcd.print(prefix); //BED + lcd_moveto(6, 6); lcd.print(i16tostr3rj(t1)); + lcd_moveto(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); + lcd_moveto(heater_id * 4, 5); lcd.print(prefix); // HE1 or HE2 or HE3 + lcd_moveto(heater_id * 4, 6); lcd.print(i16tostr3rj(t1)); + lcd_moveto(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); + lcd_moveto(13, 5); lcd.print(prefix); //BED + lcd_moveto(13, 6); lcd.print(i16tostr3rj(t1)); + lcd_moveto(13, 7); } #endif // HOTENDS <= 1 @@ -515,24 +516,24 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const FORCE_INLINE void _draw_cooler_status(const bool blink) { const celsius_t t2 = thermalManager.degTargetCooler(); - lcd.setCursor(0, 5); lcd_put_u8str(F("COOL")); - lcd.setCursor(1, 6); lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegCooler())); - lcd.setCursor(1, 7); + lcd_moveto(0, 5); lcd_put_u8str(F("COOL")); + lcd_moveto(1, 6); lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegCooler())); + lcd_moveto(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(' '); + lcd_put_lchar(' '); + if (t2 >= 10) lcd_put_lchar(' '); + if (t2 >= 100) lcd_put_lchar(' '); } else #endif lcd_put_u8str(i16tostr3left(t2)); - lcd_put_wchar(' '); - if (t2 < 10) lcd_put_wchar(' '); + lcd_put_lchar(' '); + if (t2 < 10) lcd_put_lchar(' '); if (t2) picBits |= ICON_TEMP1; else picBits &= ~ICON_TEMP1; @@ -543,9 +544,9 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if ENABLED(LASER_COOLANT_FLOW_METER) FORCE_INLINE void _draw_flowmeter_status() { - lcd.setCursor(5, 5); lcd_put_u8str(F("FLOW")); - lcd.setCursor(7, 6); lcd_put_wchar('L'); - lcd.setCursor(6, 7); lcd_put_u8str(ftostr11ns(cooler.flowrate)); + lcd_moveto(5, 5); lcd_put_u8str(F("FLOW")); + lcd_moveto(7, 6); lcd_put_lchar('L'); + lcd_moveto(6, 7); lcd_put_u8str(ftostr11ns(cooler.flowrate)); if (cooler.flowrate) picBits |= ICON_FAN; else picBits &= ~ICON_FAN; @@ -556,18 +557,18 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if ENABLED(I2C_AMMETER) FORCE_INLINE void _draw_ammeter_status() { - lcd.setCursor(10, 5); lcd_put_u8str(F("ILAZ")); + lcd_moveto(10, 5); lcd_put_u8str(F("ILAZ")); ammeter.read(); - lcd.setCursor(11, 6); + lcd_moveto(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))); + lcd_moveto(10, 7); + lcd_put_lchar(' '); lcd_put_u8str(ui16tostr3rj(uint16_t(ammeter.current * 1000 + 0.5f))); } else { lcd_put_u8str(" A"); - lcd.setCursor(10, 7); + lcd_moveto(10, 7); lcd_put_u8str(ftostr12ns(ammeter.current)); } @@ -580,16 +581,16 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if HAS_CUTTER FORCE_INLINE void _draw_cutter_status() { - lcd.setCursor(15, 5); lcd_put_u8str(F("CUTT")); + lcd_moveto(15, 5); lcd_put_u8str(F("CUTT")); #if CUTTER_UNIT_IS(RPM) - lcd.setCursor(16, 6); lcd_put_u8str(F("RPM")); - lcd.setCursor(15, 7); lcd_put_u8str(ftostr31ns(float(cutter.unitPower) / 1000)); - lcd_put_wchar('K'); + lcd_moveto(16, 6); lcd_put_u8str(F("RPM")); + lcd_moveto(15, 7); lcd_put_u8str(ftostr31ns(float(cutter.unitPower) / 1000)); + lcd_put_lchar('K'); #elif CUTTER_UNIT_IS(PERCENT) - lcd.setCursor(17, 6); lcd_put_wchar('%'); - lcd.setCursor(18, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower)); + lcd_moveto(17, 6); lcd_put_lchar('%'); + lcd_moveto(18, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower)); #else - lcd.setCursor(17, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower)); + lcd_moveto(17, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower)); #endif if (cutter.unitPower) picBits |= ICON_HOT; @@ -625,10 +626,10 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const 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_moveto(LCD_WIDTH / 2 - 2, MIDDLE_Y); + lcd.print(i16tostr3rj(percent)); lcd.write('%'); lcd.print_line(); - lcd.setCursor(0, MIDDLE_Y + 1); + lcd_moveto(0, MIDDLE_Y + 1); lcd.write('%'); lcd.write(percent); lcd.print_line(); } @@ -638,7 +639,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const void MarlinUI::draw_status_message(const bool blink) { if (!PanelDetected) return; - lcd.setCursor(0, 3); + lcd_moveto(0, 3); #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) // Alternate Status message and Filament display @@ -787,7 +788,7 @@ void MarlinUI::draw_status_screen() { // Line 1 - XYZ coordinates // - lcd.setCursor(0, 0); + lcd_moveto(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(' '); @@ -801,11 +802,11 @@ void MarlinUI::draw_status_screen() { // Line 2 - feedrate, , time // - lcd.setCursor(0, 1); + lcd_moveto(0, 1); lcd_put_u8str(F("FR")); lcd.print(i16tostr3rj(feedrate_percentage)); lcd.write('%'); #if BOTH(SDSUPPORT, HAS_PRINT_PROGRESS) - lcd.setCursor(LCD_WIDTH / 2 - 3, 1); + lcd_moveto(LCD_WIDTH / 2 - 3, 1); _draw_print_progress(); #endif @@ -813,14 +814,14 @@ void MarlinUI::draw_status_screen() { duration_t elapsed = print_job_timer.duration(); uint8_t len = elapsed.toDigital(buffer); - lcd.setCursor((LCD_WIDTH - 1) - len, 1); + lcd_moveto((LCD_WIDTH - 1) - len, 1); lcd.write(LCD_STR_CLOCK[0]); lcd.print(buffer); // // Line 3 - progressbar // - lcd.setCursor(0, 2); + lcd_moveto(0, 2); #if ENABLED(LCD_PROGRESS_BAR) draw_progress_bar(_get_progress()); #else @@ -839,7 +840,7 @@ void MarlinUI::draw_status_screen() { #if HOTENDS <= 1 || (HOTENDS <= 2 && !HAS_HEATED_BED) #if DUAL_MIXING_EXTRUDER - lcd.setCursor(0, 4); + lcd_moveto(0, 4); // Two-component mix / gradient instead of XY char mixer_messages[12]; const char *mix_label; @@ -895,9 +896,9 @@ void MarlinUI::draw_status_screen() { #else #define FANX 17 #endif - lcd.setCursor(FANX, 5); lcd_put_u8str(F("FAN")); - lcd.setCursor(FANX + 1, 6); lcd.write('%'); - lcd.setCursor(FANX, 7); + lcd_moveto(FANX, 5); lcd_put_u8str(F("FAN")); + lcd_moveto(FANX + 1, 6); lcd.write('%'); + lcd_moveto(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])) @@ -930,7 +931,7 @@ void MarlinUI::draw_status_screen() { 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_moveto((LCD_WIDTH - 14) / 2, row + 1); lcd.write(LCD_STR_THERMOMETER[0]); lcd_put_u8str(F(" 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]); @@ -940,58 +941,58 @@ void MarlinUI::draw_status_screen() { #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*/) { + void MenuItem_static::draw(const uint8_t row, FSTR_P const fstr, const uint8_t style/*=SS_DEFAULT*/, const char * const valstr/*=nullptr*/) { if (!PanelDetected) return; uint8_t n = LCD_WIDTH; - lcd.setCursor(0, row); + lcd_moveto(0, row); if ((style & SS_CENTER) && !valstr) { - int8_t pad = (LCD_WIDTH - utf8_strlen_P(pstr)) / 2; + int8_t pad = (LCD_WIDTH - utf8_strlen(fstr)) / 2; while (--pad >= 0) { lcd.write(' '); n--; } } - n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n); + n = lcd_put_u8str(fstr, itemIndex, itemStringC, itemStringF, 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) { + void MenuItemBase::_draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char pre_char, const char post_char) { if (!PanelDetected) return; - lcd.setCursor(0, row); + lcd_moveto(0, row); lcd.write(sel ? pre_char : ' '); - uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2); + uint8_t n = lcd_put_u8str(fstr, itemIndex, itemStringC, itemStringF, 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) { + void MenuEditItemBase::draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char * const inStr, const bool pgm) { if (!PanelDetected) return; - const uint8_t vlen = data ? (pgm ? utf8_strlen_P(data) : utf8_strlen(data)) : 0; - lcd.setCursor(0, row); + const uint8_t vlen = inStr ? (pgm ? utf8_strlen_P(inStr) : utf8_strlen(inStr)) : 0; + lcd_moveto(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); + uint8_t n = lcd_put_u8str(fstr, itemIndex, itemStringC, itemStringF, 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); + if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str(inStr); } 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*/) { + void MenuEditItemBase::draw_edit_screen(FSTR_P const fstr, 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_moveto(0, y); lcd.write(COLOR_EDIT); - lcd_put_u8str_P(pstr); + lcd_put_u8str(fstr); if (value) { lcd.write(':'); - lcd.setCursor((LCD_WIDTH - 1) - (utf8_strlen(value) + 1), y); // Right-justified, padded by spaces + lcd_moveto((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(' '); @@ -1000,26 +1001,26 @@ void MarlinUI::draw_status_screen() { } // 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) { + void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, const bool yesno, FSTR_P const pref, const char * const string, FSTR_P const suff) { if (!PanelDetected) return; ui.draw_select_screen_prompt(pref, string, suff); lcd.write(COLOR_EDIT); if (no) { - lcd.setCursor(0, MIDDLE_Y); - lcd.write(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd.write(yesno ? ' ' : ']'); + lcd_moveto(0, MIDDLE_Y); + lcd.write(yesno ? ' ' : '['); lcd_put_u8str(no); lcd.write(yesno ? ' ' : ']'); } if (yes) { - lcd.setCursor(LCD_WIDTH - utf8_strlen_P(yes) - 3, MIDDLE_Y); - lcd.write(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd.write(yesno ? ']' : ' '); + lcd_moveto(LCD_WIDTH - utf8_strlen(yes) - 3, MIDDLE_Y); + lcd.write(yesno ? '[' : ' '); lcd_put_u8str(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) { + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { if (!PanelDetected) return; - lcd.setCursor(0, row); + lcd_moveto(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); @@ -1058,30 +1059,30 @@ void MarlinUI::draw_status_screen() { lcd.clear_buffer(); //print only top left corner. All frame with grid points will be printed by panel - lcd.setCursor(0, 0); + lcd_moveto(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 = ')'; + lcd_moveto(_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(F("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(F("Y:")); - lcd.print(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + lcd_moveto(_LCD_W_POS, 1); lcd_put_u8str(F("X:")); + lcd.print(ftostr52(LOGICAL_X_POSITION(pgm_read_float(&bedlevel._mesh_index_to_xpos[x_plot])))); + lcd_moveto(_LCD_W_POS, 2); lcd_put_u8str(F("Y:")); + lcd.print(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&bedlevel._mesh_index_to_ypos[y_plot])))); // Show the location value - lcd.setCursor(_LCD_W_POS, 3); lcd_put_u8str(F("Z:")); + lcd_moveto(_LCD_W_POS, 3); lcd_put_u8str(F("Z:")); - if (!isnan(ubl.z_values[x_plot][y_plot])) - lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + if (!isnan(bedlevel.z_values[x_plot][y_plot])) + lcd.print(ftostr43sign(bedlevel.z_values[x_plot][y_plot])); else lcd_put_u8str(F(" -----")); - center_text_P(GET_TEXT(MSG_UBL_FINE_TUNE_MESH), 8); + center_text(GET_TEXT_F(MSG_UBL_FINE_TUNE_MESH), 8); lcd.print_screen(); } diff --git a/Marlin/src/lcd/buttons.h b/Marlin/src/lcd/buttons.h index 429fb971ec83..2580a71d1b82 100644 --- a/Marlin/src/lcd/buttons.h +++ b/Marlin/src/lcd/buttons.h @@ -26,7 +26,7 @@ #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) +#if (HAS_ENCODER_WHEEL || ANY_BUTTON(ENC, BACK, UP, DWN, LFT, RT)) && DISABLED(TOUCH_UI_FTDI_EVE) #define HAS_DIGITAL_BUTTONS 1 #endif #if !HAS_ADC_BUTTONS && (IS_RRW_KEYPAD || (HAS_WIRED_LCD && !IS_NEWPANEL)) diff --git a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h index e5c6524a9ec4..f38c9d76e3ba 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h @@ -124,7 +124,7 @@ #ifndef U8G_COM_SSD_I2C_HAL #define U8G_COM_SSD_I2C_HAL u8g_com_null_fn #endif -#if HAS_FSMC_GRAPHICAL_TFT || HAS_SPI_GRAPHICAL_TFT +#if HAS_FSMC_GRAPHICAL_TFT || HAS_SPI_GRAPHICAL_TFT || HAS_LTDC_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/lcdprint_u8g.cpp b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp index f74a59a08c7c..48b2e92a118d 100644 --- a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp +++ b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp @@ -28,7 +28,7 @@ void lcd_put_int(const int i) { u8g.print(i); } // return < 0 on error // return the advanced pixels -int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { +int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { if (c < 256) { u8g.print((char)c); return u8g_GetFontBBXWidth(u8g.getU8g()); @@ -39,14 +39,14 @@ int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { return ret; } -int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { +int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { u8g_uint_t x = u8g.getPrintCol(), y = u8g.getPrintRow(), ret = uxg_DrawUtf8Str(u8g.getU8g(), x, y, utf8_str, max_length); u8g.setPrintPos(x + ret, y); return ret; } -int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P utf8_pstr, const pixel_len_t max_length) { u8g_uint_t x = u8g.getPrintCol(), y = u8g.getPrintRow(), ret = uxg_DrawUtf8StrP(u8g.getU8g(), x, y, utf8_pstr, max_length); u8g.setPrintPos(x + ret, y); diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 19611f678d31..e32715988d2f 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -330,13 +330,13 @@ void MarlinUI::update_language_font() { // 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; + const u8g_uint_t x = 0, h4 = u8g.getHeight() / 4; u8g.firstPage(); do { set_font(FONT_MENU); - lcd_put_u8str(0, h4 * 1, status_message); - lcd_put_u8str(0, h4 * 2, GET_TEXT_F(MSG_HALTED)); - lcd_put_u8str(0, h4 * 3, GET_TEXT_F(MSG_PLEASE_RESET)); + lcd_put_u8str(x, h4 * 1, status_message); + lcd_put_u8str(x, h4 * 2, GET_TEXT_F(MSG_HALTED)); + lcd_put_u8str(x, h4 * 3, GET_TEXT_F(MSG_PLEASE_RESET)); } while (u8g.nextPage()); } @@ -371,11 +371,11 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop if (!PAGE_CONTAINS(y1 + 1, y2 + 2)) return; - lcd_put_wchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), y2, 'E'); - lcd_put_wchar((char)('1' + extruder)); - lcd_put_wchar(' '); + lcd_put_lchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), y2, 'E'); + lcd_put_lchar((char)('1' + extruder)); + lcd_put_lchar(' '); lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); - lcd_put_wchar('/'); + lcd_put_lchar('/'); if (get_blink() || !thermalManager.heater_idle[extruder].timed_out) lcd_put_u8str(i16tostr3rj(thermalManager.degTargetHotend(extruder))); @@ -412,56 +412,56 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop } // 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*/) { + void MenuItem_static::draw(const uint8_t row, FSTR_P const ftpl, 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, + const int plen = ftpl ? calculateWidth(ftpl) : 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(' '); + while (--pad >= 0) n -= lcd_put_lchar(' '); } - if (plen) n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n / (MENU_FONT_WIDTH)) * (MENU_FONT_WIDTH); + if (plen) n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, 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(' '); + while (n > MENU_FONT_WIDTH) n -= lcd_put_lchar(' '); } } // 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) { + void MenuItemBase::_draw(const bool sel, const uint8_t row, FSTR_P const ftpl, 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(' '); + pixel_len_t n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 1) * (MENU_FONT_WIDTH); + while (n > MENU_FONT_WIDTH) n -= lcd_put_lchar(' '); + lcd_put_lchar(LCD_PIXEL_WIDTH - (MENU_FONT_WIDTH), row_y2, post_char); + lcd_put_lchar(' '); } } // 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) { + void MenuEditItemBase::draw(const bool sel, const uint8_t row, FSTR_P const ftpl, 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 uint8_t vallen = (pgm ? utf8_strlen_P(inStr) : utf8_strlen(inStr)), + pixelwidth = (pgm ? uxg_GetUtf8StrPixelWidthP(u8g.getU8g(), inStr) : uxg_GetUtf8StrPixelWidth(u8g.getU8g(), 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); + pixel_len_t n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 2 - vallen * prop) * (MENU_FONT_WIDTH); if (vallen) { - lcd_put_wchar(':'); - while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); + lcd_put_lchar(':'); + while (n > MENU_FONT_WIDTH) n -= lcd_put_lchar(' '); 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); + if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str(inStr); } } } - void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { + void MenuEditItemBase::draw_edit_screen(FSTR_P const ftpl, 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); + const u8g_uint_t labellen = utf8_strlen(ftpl), vallen = utf8_strlen(value); bool extra_row = labellen * prop > LCD_WIDTH - 2 - vallen * prop; #if ENABLED(USE_BIG_EDIT_FONT) @@ -490,26 +490,26 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop // 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 (onpage) lcd_put_u8str(0, baseline, ftpl, itemIndex, itemStringC, itemStringF); // If a value is included, print a colon, then print the value right-justified if (value) { - lcd_put_wchar(':'); + lcd_put_lchar(':'); 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_lchar(((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), + inline void draw_boxed_string(const u8g_uint_t x, const u8g_uint_t y, FSTR_P const fstr, const bool inv) { + const u8g_uint_t len = utf8_strlen(fstr), 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); @@ -518,25 +518,25 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop 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); + lcd_put_u8str(bx / prop, by, fstr); 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); + void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, const bool yesno, FSTR_P const fpre, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/) { + ui.draw_select_screen_prompt(fpre, string, suff); if (no) draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno); - if (yes) draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) * (USE_WIDE_GLYPH ? 2 : 1) + 1), LCD_HEIGHT - 1, yes, yesno); + if (yes) draw_boxed_string(LCD_WIDTH - (utf8_strlen(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) { + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { if (mark_as_selected(row, sel)) { const uint8_t maxlen = LCD_WIDTH - isDir; - if (isDir) lcd_put_wchar(LCD_STR_FOLDER[0]); + if (isDir) lcd_put_lchar(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(' '); + while (n > MENU_FONT_WIDTH) n -= lcd_put_lchar(' '); } } @@ -579,9 +579,9 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop 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) + 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) + 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 @@ -601,7 +601,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop // 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) }, + const xy_pos_t pos = { bedlevel.get_mesh_x(x_plot), bedlevel.get_mesh_y(y_plot) }, lpos = pos.asLogical(); lcd_put_u8str_P(5, 7, X_LBL); lcd_put_u8str(ftostr52(lpos.x)); @@ -611,16 +611,16 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop // Print plot position if (PAGE_CONTAINS(LCD_PIXEL_HEIGHT - (INFO_FONT_HEIGHT - 1), LCD_PIXEL_HEIGHT)) { - lcd_put_wchar(5, LCD_PIXEL_HEIGHT, '('); + lcd_put_lchar(5, LCD_PIXEL_HEIGHT, '('); u8g.print(x_plot); - lcd_put_wchar(','); + lcd_put_lchar(','); u8g.print(y_plot); - lcd_put_wchar(')'); + lcd_put_lchar(')'); // 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])); + if (!isnan(bedlevel.z_values[x_plot][y_plot])) + lcd_put_u8str(ftostr43sign(bedlevel.z_values[x_plot][y_plot])); else lcd_put_u8str(F(" -----")); } diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 47b5a3e20b0a..67039d52de7b 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -200,7 +200,7 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co 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]); + lcd_put_lchar(LCD_STR_DEGREE[0]); } } @@ -432,13 +432,13 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const 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 = a * (is_inch ? XYZ_SPACING_IN : XYZ_SPACING); - lcd_put_wchar((is_inch ? X_LABEL_POS_IN : X_LABEL_POS) + offs, XYZ_BASELINE, AXIS_CHAR(axis)); + lcd_put_lchar((is_inch ? X_LABEL_POS_IN : X_LABEL_POS) + offs, XYZ_BASELINE, AXIS_CHAR(axis)); lcd_moveto((is_inch ? X_VALUE_POS_IN : X_VALUE_POS) + offs, XYZ_BASELINE); if (blink) lcd_put_u8str(value); else if (axis_should_home(axis)) - while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); + while (const char c = *value++) lcd_put_lchar(c <= '.' ? c : '?'); else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) lcd_put_u8str(axis == Z_AXIS ? F(" ") : F(" ")); else @@ -670,12 +670,12 @@ void MarlinUI::draw_status_screen() { // Laser / Spindle #if DO_DRAW_CUTTER - if (cutter.isReady && PAGE_CONTAINS(STATUS_CUTTER_TEXT_Y - INFO_FONT_ASCENT, STATUS_CUTTER_TEXT_Y - 1)) { + if (cutter.isReadyForUI && 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)); #elif CUTTER_UNIT_IS(RPM) lcd_put_u8str(STATUS_CUTTER_TEXT_X - 2, STATUS_CUTTER_TEXT_Y, ftostr61rj(float(cutter.unitPower) / 1000)); - lcd_put_wchar('K'); + lcd_put_lchar('K'); #else lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, cutter_power2str(cutter.unitPower)); #endif @@ -734,7 +734,7 @@ void MarlinUI::draw_status_screen() { } #endif lcd_put_u8str(STATUS_FAN_TEXT_X, STATUS_FAN_TEXT_Y, i16tostr3rj(thermalManager.pwmToPercent(spd))); - lcd_put_wchar(c); + lcd_put_lchar(c); } } #endif @@ -783,7 +783,7 @@ void MarlinUI::draw_status_screen() { if (progress_state == 0) { if (progress_string[0]) { lcd_put_u8str(progress_x_pos, EXTRAS_BASELINE, progress_string); - lcd_put_wchar('%'); + lcd_put_lchar('%'); } } else if (progress_state == 2 && estimation_string[0]) { @@ -791,7 +791,7 @@ void MarlinUI::draw_status_screen() { lcd_put_u8str(estimation_x_pos, EXTRAS_BASELINE, estimation_string); } else if (elapsed_string[0]) { - lcd_put_u8str_P(PROGRESS_BAR_X, EXTRAS_BASELINE, E_LBL); + lcd_put_u8str(PROGRESS_BAR_X, EXTRAS_BASELINE, F("E:")); lcd_put_u8str(elapsed_x_pos, EXTRAS_BASELINE, elapsed_string); } @@ -804,7 +804,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(SHOW_SD_PERCENT) if (progress_string[0]) { lcd_put_u8str(55, EXTRAS_BASELINE, progress_string); // Percent complete - lcd_put_wchar('%'); + lcd_put_lchar('%'); } #endif @@ -814,7 +814,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(SHOW_REMAINING_TIME) if (blink && estimation_string[0]) { - lcd_put_wchar(estimation_x_pos, EXTRAS_BASELINE, 'R'); + lcd_put_lchar(estimation_x_pos, EXTRAS_BASELINE, 'R'); lcd_put_u8str(estimation_string); } else @@ -912,11 +912,11 @@ void MarlinUI::draw_status_screen() { if (PAGE_CONTAINS(EXTRAS_2_BASELINE - INFO_FONT_ASCENT, EXTRAS_2_BASELINE - 1)) { set_font(FONT_MENU); - lcd_put_wchar(3, EXTRAS_2_BASELINE, LCD_STR_FEEDRATE[0]); + lcd_put_lchar(3, EXTRAS_2_BASELINE, LCD_STR_FEEDRATE[0]); set_font(FONT_STATUSMENU); lcd_put_u8str(12, EXTRAS_2_BASELINE, i16tostr3rj(feedrate_percentage)); - lcd_put_wchar('%'); + lcd_put_lchar('%'); // // Filament sensor display if SD is disabled @@ -924,10 +924,10 @@ void MarlinUI::draw_status_screen() { #if ENABLED(FILAMENT_LCD_DISPLAY) && DISABLED(SDSUPPORT) lcd_put_u8str(56, EXTRAS_2_BASELINE, wstring); lcd_put_u8str(102, EXTRAS_2_BASELINE, mstring); - lcd_put_wchar('%'); + lcd_put_lchar('%'); set_font(FONT_MENU); - lcd_put_wchar(47, EXTRAS_2_BASELINE, LCD_STR_FILAM_DIA[0]); // lcd_put_u8str(F(LCD_STR_FILAM_DIA)); - lcd_put_wchar(93, EXTRAS_2_BASELINE, LCD_STR_FILAM_MUL[0]); + lcd_put_lchar(47, EXTRAS_2_BASELINE, LCD_STR_FILAM_DIA[0]); // lcd_put_u8str(F(LCD_STR_FILAM_DIA)); + lcd_put_lchar(93, EXTRAS_2_BASELINE, LCD_STR_FILAM_MUL[0]); #endif } @@ -941,12 +941,12 @@ void MarlinUI::draw_status_screen() { // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { lcd_put_u8str(F(LCD_STR_FILAM_DIA)); - lcd_put_wchar(':'); + lcd_put_lchar(':'); lcd_put_u8str(wstring); lcd_put_u8str(F(" " LCD_STR_FILAM_MUL)); - lcd_put_wchar(':'); + lcd_put_lchar(':'); lcd_put_u8str(mstring); - lcd_put_wchar('%'); + lcd_put_lchar('%'); return; } #endif @@ -979,7 +979,7 @@ void MarlinUI::draw_status_message(const bool blink) { if (slen <= lcd_width) { // The string fits within the line. Print with no scrolling lcd_put_u8str(status_message); - while (slen < lcd_width) { lcd_put_wchar(' '); ++slen; } + while (slen < lcd_width) { lcd_put_lchar(' '); ++slen; } } else { // String is longer than the available space @@ -997,14 +997,14 @@ void MarlinUI::draw_status_message(const bool blink) { // 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 + lcd_put_lchar(' '); // Always at 1+ spaces left, draw a space if (--chars) { // Draw a second space if there's room - lcd_put_wchar(' '); + lcd_put_lchar(' '); if (--chars) { // Draw a third space if there's room - lcd_put_wchar(' '); + lcd_put_lchar(' '); 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(' '); + lcd_put_lchar(' '); } } } @@ -1019,7 +1019,7 @@ void MarlinUI::draw_status_message(const bool blink) { lcd_put_u8str_max(status_message, pixel_width); // Fill the rest with spaces - for (; slen < lcd_width; ++slen) lcd_put_wchar(' '); + for (; slen < lcd_width; ++slen) lcd_put_lchar(' '); #endif // !STATUS_MESSAGE_SCROLLING 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 bfd44d08dfbb..63e7b2e2b8b5 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp @@ -74,7 +74,6 @@ #define ST7565_ON(N) ((N) ? 0xAF : 0xAE) #define ST7565_OUT_MODE(N) ((N) ? 0xC8 : 0xC0) #define ST7565_POWER_CONTROL(N) (0x28 | (N)) -#define ST7565_V0_RATIO(N) (0x10 | ((N) & 0x7)) #define ST7565_V5_RATIO(N) (0x20 | ((N) & 0x7)) #define ST7565_CONTRAST(N) (0x81), (N) @@ -106,11 +105,14 @@ static const uint8_t u8g_dev_st7565_64128n_HAL_init_seq[] PROGMEM = { ST7565_POWER_CONTROL(0x7), // power control: turn on voltage follower U8G_ESC_DLY(50), // delay 50 ms - ST7565_V0_RATIO(0), // Set V0 voltage resistor ratio. Setting for controlling brightness of Displaytech 64128N + #ifdef ST7565_VOLTAGE_DIVIDER_VALUE + // Set V5 voltage resistor ratio. Affects brightness of Displaytech 64128N + ST7565_V5_RATIO(ST7565_VOLTAGE_DIVIDER_VALUE), + #endif ST7565_INVERTED(0), // display normal, bit val 0: LCD pixel off. - ST7565_CONTRAST(0x1E), // Contrast value. Setting for controlling brightness of Displaytech 64128N + ST7565_CONTRAST(0x1E), // Contrast value for Displaytech 64128N ST7565_ON(1), // display on 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 4a794f500007..f1bf9d032ec8 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 @@ -517,14 +517,14 @@ U8G_PB_DEV(u8g_dev_tft_320x240_upscale_from_128x64, WIDTH, HEIGHT, PAGE_HEIGHT, drawCross(x, y, TFT_MARLINBG_COLOR); } - const char *str = nullptr; + FSTR_P 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; + case CALIBRATION_TOP_LEFT: str = GET_TEXT_F(MSG_TOP_LEFT); break; + case CALIBRATION_BOTTOM_LEFT: str = GET_TEXT_F(MSG_BOTTOM_LEFT); break; + case CALIBRATION_TOP_RIGHT: str = GET_TEXT_F(MSG_TOP_RIGHT); break; + case CALIBRATION_BOTTOM_RIGHT: str = GET_TEXT_F(MSG_BOTTOM_RIGHT); break; default: break; } @@ -534,7 +534,7 @@ U8G_PB_DEV(u8g_dev_tft_320x240_upscale_from_128x64, WIDTH, HEIGHT, PAGE_HEIGHT, } else { // end calibration - str = calibration_stage == CALIBRATION_SUCCESS ? GET_TEXT(MSG_CALIBRATION_COMPLETED) : GET_TEXT(MSG_CALIBRATION_FAILED); + str = calibration_stage == CALIBRATION_SUCCESS ? GET_TEXT_F(MSG_CALIBRATION_COMPLETED) : GET_TEXT_F(MSG_CALIBRATION_FAILED); defer_status_screen(false); touch_calibration.calibration_end(); TERN_(HAS_TOUCH_BUTTONS, redrawTouchButtons = true); diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.cpp b/Marlin/src/lcd/dogm/u8g_fontutf8.cpp index 89bdb09e1be2..d5e0e5bafff3 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.cpp +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.cpp @@ -60,11 +60,11 @@ static int fontgroup_init(font_group_t * root, const uxg_fontinfo_t * fntinfo, i return 0; } -static const font_t* fontgroup_find(font_group_t * root, wchar_t val) { - uxg_fontinfo_t vcmp = {(uint16_t)(val / 128), (uint8_t)(val % 128 + 128), (uint8_t)(val % 128 + 128), 0, 0}; - size_t idx = 0; +static const font_t* fontgroup_find(font_group_t * root, const lchar_t &val) { + if (val <= 0xFF) return nullptr; - if (val < 256) return nullptr; + uxg_fontinfo_t vcmp = { uint16_t(val >> 7), uint8_t((val & 0x7F) + 0x80), uint8_t((val & 0x7F) + 0x80), 0, 0 }; + size_t idx = 0; if (pf_bsearch_r((void*)root->m_fntifo, root->m_fntinfo_num, pf_bsearch_cb_comp_fntifo_pgm, (void*)&vcmp, &idx) < 0) return nullptr; @@ -73,7 +73,7 @@ static const font_t* fontgroup_find(font_group_t * root, wchar_t val) { return vcmp.fntdata; } -static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default, wchar_t val, void * userdata, fontgroup_cb_draw_t cb_draw_ram) { +static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default, const lchar_t &val, void * userdata, fontgroup_cb_draw_t cb_draw_ram) { uint8_t buf[2] = {0, 0}; const font_t * fntpqm = (font_t*)fontgroup_find(group, val); if (!fntpqm) { @@ -104,12 +104,12 @@ static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default, * Get the screen pixel width of a ROM UTF-8 string */ static void fontgroup_drawstring(font_group_t *group, const font_t *fnt_default, const char *utf8_msg, read_byte_cb_t cb_read_byte, void * userdata, fontgroup_cb_draw_t cb_draw_ram) { - uint8_t *p = (uint8_t*)utf8_msg; + const uint8_t *p = (uint8_t*)utf8_msg; for (;;) { - wchar_t val = 0; - p = get_utf8_value_cb(p, cb_read_byte, &val); - if (!val) break; - fontgroup_drawwchar(group, fnt_default, val, userdata, cb_draw_ram); + lchar_t wc; + p = get_utf8_value_cb(p, cb_read_byte, wc); + if (!wc) break; + fontgroup_drawwchar(group, fnt_default, wc, userdata, cb_draw_ram); } } @@ -149,19 +149,19 @@ static int fontgroup_cb_draw_u8g(void *userdata, const font_t *fnt_current, cons } /** - * @brief Draw a wchar_t at the specified position + * @brief Draw a lchar_t at the specified position * * @param pu8g : U8G pointer * @param x : position x axis * @param y : position y axis - * @param ch : the wchar_t + * @param wc : the lchar_t * @param max_width : the pixel width of the string allowed * * @return number of pixels advanced * * Draw a UTF-8 string at the specified position */ -unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, wchar_t ch, pixel_len_t max_width) { +unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, const lchar_t &wc, pixel_len_t max_width) { struct _uxg_drawu8_data_t data; font_group_t *group = &g_fontgroup_root; const font_t *fnt_default = uxg_GetFont(pu8g); @@ -176,7 +176,7 @@ unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, wchar_t data.adv = 0; data.max_width = max_width; data.fnt_prev = nullptr; - fontgroup_drawwchar(group, fnt_default, ch, (void*)&data, fontgroup_cb_draw_u8g); + fontgroup_drawwchar(group, fnt_default, wc, (void*)&data, fontgroup_cb_draw_u8g); u8g_SetFont(pu8g, (const u8g_fntpgm_uint8_t*)fnt_default); return data.adv; diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.h b/Marlin/src/lcd/dogm/u8g_fontutf8.h index 9760ef106bd1..0109b6674cbe 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.h +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.h @@ -26,10 +26,10 @@ typedef struct _uxg_fontinfo_t { int uxg_SetUtf8Fonts(const uxg_fontinfo_t * fntinfo, int number); // fntinfo is type of PROGMEM -unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, wchar_t ch, pixel_len_t max_length); +unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, const lchar_t &ch, const pixel_len_t max_length); -unsigned int uxg_DrawUtf8Str(u8g_t *pu8g, unsigned int x, unsigned int y, const char *utf8_msg, pixel_len_t max_length); -unsigned int uxg_DrawUtf8StrP(u8g_t *pu8g, unsigned int x, unsigned int y, PGM_P utf8_msg, pixel_len_t max_length); +unsigned int uxg_DrawUtf8Str(u8g_t *pu8g, unsigned int x, unsigned int y, const char *utf8_msg, const pixel_len_t max_length); +unsigned int uxg_DrawUtf8StrP(u8g_t *pu8g, unsigned int x, unsigned int y, PGM_P utf8_msg, const pixel_len_t max_length); int uxg_GetUtf8StrPixelWidth(u8g_t *pu8g, const char *utf8_msg); int uxg_GetUtf8StrPixelWidthP(u8g_t *pu8g, PGM_P utf8_msg); diff --git a/Marlin/src/lcd/e3v2/README.md b/Marlin/src/lcd/e3v2/README.md index 10b05455fdaf..91f25e2433bf 100644 --- a/Marlin/src/lcd/e3v2/README.md +++ b/Marlin/src/lcd/e3v2/README.md @@ -1,6 +1,6 @@ # DWIN for Creality Ender 3 v2 -Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.0.x/config/examples/Creality/Ender-3%20V2). +Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.1.x/config/examples/Creality/Ender-3%20V2). ## Easy Install diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index 63a75b89c8af..3f699465a9c8 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -234,7 +234,9 @@ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, // *string: The string // rlimit: To limit the drawn string length void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit/*=0xFFFF*/) { - DWIN_Draw_Rectangle(1, bColor, x, y, x + (fontWidth(size) * strlen_P(string)), y + fontHeight(size)); + #if DISABLED(DWIN_LCD_PROUI) + DWIN_Draw_Rectangle(1, bColor, x, y, x + (fontWidth(size) * strlen_P(string)), y + fontHeight(size)); + #endif constexpr uint8_t widthAdjust = 0; size_t i = 0; DWIN_Byte(i, 0x11); diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h index 37b1525ba34a..dc97ef2723fa 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -74,7 +74,7 @@ inline void DWIN_Text(size_t &i, const char * const string, uint16_t rlimit=0xFF inline void DWIN_Text(size_t &i, FSTR_P string, uint16_t rlimit=0xFFFF) { if (!string) return; - const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(rlimit, strlen_P((PGM_P)string))); // cast to PGM_P (const char*) measure with strlen_P. + const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(rlimit, strlen_P(FTOP(string)))); if (len == 0) return; memcpy_P(&DWIN_SendBuf[i+1], string, len); i += len; @@ -176,9 +176,13 @@ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit=0xFFFF); inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, FSTR_P const ftitle) { - char ctitle[strlen_P(FTOP(ftitle)) + 1]; - strcpy_P(ctitle, FTOP(ftitle)); - DWIN_Draw_String(bShow, size, color, bColor, x, y, ctitle); + #ifdef __AVR__ + char ctitle[strlen_P(FTOP(ftitle)) + 1]; + strcpy_P(ctitle, FTOP(ftitle)); + DWIN_Draw_String(bShow, size, color, bColor, x, y, ctitle); + #else + DWIN_Draw_String(bShow, size, color, bColor, x, y, FTOP(ftitle)); + #endif } // Draw a positive integer diff --git a/Marlin/src/lcd/e3v2/common/encoder.cpp b/Marlin/src/lcd/e3v2/common/encoder.cpp index edfaf60aae1e..9922b70b29df 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.cpp +++ b/Marlin/src/lcd/e3v2/common/encoder.cpp @@ -51,11 +51,7 @@ ENCODER_Rate EncoderRate; // TODO: Replace with ui.quick_feedback void Encoder_tick() { #if PIN_EXISTS(BEEPER) - if (ui.buzzer_enabled) { - WRITE(BEEPER_PIN, HIGH); - delay(10); - WRITE(BEEPER_PIN, LOW); - } + if (ui.sound_on) buzzer.click(10); #endif } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 05ac38d226ce..3ca7627db086 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -33,7 +33,7 @@ //#define USE_STRING_HEADINGS //#define USE_STRING_TITLES -#if ENABLED(LCD_BED_LEVELING) && DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) +#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) #define HAS_ONESTEP_LEVELING 1 #endif @@ -1366,8 +1366,6 @@ void HMI_Move_Z() { #if HAS_ZOFFSET_ITEM - bool printer_busy() { return planner.movesplanned() || printingIsActive(); } - void HMI_Zoffset() { EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2730,7 +2728,7 @@ void HMI_Prepare() { EncoderRate.enabled = true; #else // Apply workspace offset, making the current position 0,0,0 - queue.inject(F("G92 X0 Y0 Z0")); + queue.inject(F("G92X0Y0Z0")); HMI_AudioFeedback(); #endif break; @@ -3558,9 +3556,9 @@ void HMI_AdvSet() { case ADVSET_CASE_HOMEOFF: 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; + HMI_ValueStruct.Home_OffX_scaled = home_offset.x * 10; + HMI_ValueStruct.Home_OffY_scaled = home_offset.y * 10; + HMI_ValueStruct.Home_OffZ_scaled = home_offset.z * 10; Draw_HomeOff_Menu(); break; #endif @@ -3808,7 +3806,7 @@ void HMI_Tune() { EncoderRate.enabled = true; #else // Apply workspace offset, making the current position 0,0,0 - queue.inject(F("G92 X0 Y0 Z0")); + queue.inject(F("G92X0Y0Z0")); HMI_AudioFeedback(); #endif break; @@ -4309,9 +4307,13 @@ void DWIN_StatusChanged(const char * const cstr/*=nullptr*/) { } void DWIN_StatusChanged(FSTR_P const fstr) { - char str[strlen_P(FTOP(fstr)) + 1]; - strcpy_P(str, FTOP(fstr)); - DWIN_StatusChanged(str); + #ifdef __AVR__ + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); + DWIN_StatusChanged(str); + #else + DWIN_StatusChanged(FTOP(fstr)); + #endif } #endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/e3v2/jyersui/README.md b/Marlin/src/lcd/e3v2/jyersui/README.md deleted file mode 100644 index 10b05455fdaf..000000000000 --- a/Marlin/src/lcd/e3v2/jyersui/README.md +++ /dev/null @@ -1,7 +0,0 @@ -# DWIN for Creality Ender 3 v2 - -Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.0.x/config/examples/Creality/Ender-3%20V2). - -## Easy Install - -Copy the `DWIN_SET` folder onto a Micro-SD card and insert the card into the slot on the DWIN screen. Cycle the machine and wait for the screen to go from blue to orange. Turn the machine off and remove the SD card. When you turn on the machine the screen will display a "Creality" loading screen. diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp deleted file mode 100644 index fd51ab468639..000000000000 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ /dev/null @@ -1,4685 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -/** - * lcd/e3v2/jyersui/dwin.cpp - */ - -#include "../../../inc/MarlinConfigPre.h" - -#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) - -#include "dwin.h" - -#include "../../marlinui.h" -#include "../../../MarlinCore.h" - -#include "../../../gcode/gcode.h" -#include "../../../module/temperature.h" -#include "../../../module/planner.h" -#include "../../../module/settings.h" -#include "../../../libs/buzzer.h" -#include "../../../inc/Conditionals_post.h" - -//#define DEBUG_OUT 1 -#include "../../../core/debug_out.h" - -#if ENABLED(ADVANCED_PAUSE_FEATURE) - #include "../../../feature/pause.h" -#endif - -#if ENABLED(FILAMENT_RUNOUT_SENSOR) - #include "../../../feature/runout.h" -#endif - -#if ENABLED(HOST_ACTION_COMMANDS) - #include "../../../feature/host_actions.h" -#endif - -#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) - #define HAS_ZOFFSET_ITEM 1 -#endif - -#ifndef strcasecmp_P - #define strcasecmp_P(a, b) strcasecmp((a), (b)) -#endif - -#if HAS_LEVELING - #include "../../../feature/bedlevel/bedlevel.h" -#endif - -#if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../../../libs/least_squares_fit.h" - #include "../../../libs/vector_3.h" -#endif - -#if HAS_BED_PROBE - #include "../../../module/probe.h" -#endif - -#if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../feature/powerloss.h" -#endif - -#define MACHINE_SIZE STRINGIFY(X_BED_SIZE) "x" STRINGIFY(Y_BED_SIZE) "x" STRINGIFY(Z_MAX_POS) - -#define DWIN_FONT_MENU font8x16 -#define DWIN_FONT_STAT font10x20 -#define DWIN_FONT_HEAD font10x20 - -#define MENU_CHAR_LIMIT 24 -#define STATUS_Y 352 - -#define MAX_PRINT_SPEED 500 -#define MIN_PRINT_SPEED 10 - -#if HAS_FAN - #define MAX_FAN_SPEED 255 - #define MIN_FAN_SPEED 0 -#endif - -#define MAX_XY_OFFSET 100 - -#if HAS_ZOFFSET_ITEM - #define MAX_Z_OFFSET 9.99 - #if HAS_BED_PROBE - #define MIN_Z_OFFSET -9.99 - #else - #define MIN_Z_OFFSET -1 - #endif -#endif - -#if HAS_HOTEND - #define MAX_FLOW_RATE 200 - #define MIN_FLOW_RATE 10 - - #define MAX_E_TEMP (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT) - #define MIN_E_TEMP 0 -#endif - -#if HAS_HEATED_BED - #define MAX_BED_TEMP BED_MAXTEMP - #define MIN_BED_TEMP 0 -#endif - -constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, - TITLE_HEIGHT = 30, - MLINE = 53, - LBLX = 60, - MENU_CHR_W = 8, MENU_CHR_H = 16, STAT_CHR_W = 10; - -#define MBASE(L) (49 + MLINE * (L)) - -constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; -constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; -constexpr float default_steps[] = DEFAULT_AXIS_STEPS_PER_UNIT; -#if HAS_CLASSIC_JERK - constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; -#endif - -enum SelectItem : uint8_t { - PAGE_PRINT = 0, - PAGE_PREPARE, - PAGE_CONTROL, - PAGE_INFO_LEVELING, - PAGE_COUNT, - - PRINT_SETUP = 0, - PRINT_PAUSE_RESUME, - PRINT_STOP, - PRINT_COUNT -}; - -uint8_t active_menu = MainMenu, last_menu = MainMenu; -uint8_t selection = 0, last_selection = 0; -uint8_t scrollpos = 0; -uint8_t process = Main, last_process = Main; -PopupID popup, last_popup; - -void (*funcpointer)() = nullptr; -void *valuepointer = nullptr; -float tempvalue; -float valuemin; -float valuemax; -uint8_t valueunit; -uint8_t valuetype; - -char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16], str_3[16]; -char statusmsg[64]; -char filename[LONG_FILENAME_LENGTH]; -bool printing = false; -bool paused = false; -bool sdprint = false; - -int16_t pausetemp, pausebed, pausefan; - -bool livemove = false; -bool liveadjust = false; -uint8_t preheatmode = 0; -float zoffsetvalue = 0; -uint8_t gridpoint; -float corner_avg; -float corner_pos; - -bool probe_deployed = false; - -CrealityDWINClass CrealityDWIN; - -#if HAS_MESH - - struct Mesh_Settings { - bool viewer_asymmetric_range = false; - bool viewer_print_value = false; - bool goto_mesh_value = false; - bool drawing_mesh = false; - uint8_t mesh_x = 0; - uint8_t mesh_y = 0; - - #if ENABLED(AUTO_BED_LEVELING_UBL) - uint8_t tilt_grid = 1; - - void manual_value_update(bool undefined=false) { - sprintf_P(cmd, PSTR("M421 I%i J%i Z%s %s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1), undefined ? "N" : ""); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - } - - bool create_plane_from_mesh() { - struct linear_fit_data lsf_results; - incremental_LSF_reset(&lsf_results); - GRID_LOOP(x, y) { - if (!isnan(Z_VALUES_ARR[x][y])) { - xy_pos_t rpos; - rpos.x = ubl.mesh_index_to_xpos(x); - rpos.y = ubl.mesh_index_to_ypos(y); - incremental_LSF(&lsf_results, rpos, Z_VALUES_ARR[x][y]); - } - } - - if (finish_incremental_LSF(&lsf_results)) { - SERIAL_ECHOPGM("Could not complete LSF!"); - return true; - } - - ubl.set_all_mesh_points_to_value(0); - - matrix_3x3 rotation = matrix_3x3::create_look_at(vector_3(lsf_results.A, lsf_results.B, 1)); - GRID_LOOP(i, j) { - float mx = ubl.mesh_index_to_xpos(i), - my = ubl.mesh_index_to_ypos(j), - mz = Z_VALUES_ARR[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); - } - - rotation.apply_rotation_xyz(mx, my, mz); - - 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); - } - - Z_VALUES_ARR[i][j] = mz - lsf_results.D; - } - return false; - } - - #else - - void manual_value_update() { - sprintf_P(cmd, PSTR("G29 I%i J%i Z%s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - } - - #endif - - void manual_move(bool zmove=false) { - if (zmove) { - planner.synchronize(); - current_position.z = goto_mesh_value ? Z_VALUES_ARR[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; - planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); - planner.synchronize(); - } - else { - CrealityDWIN.Popup_Handler(MoveWait); - sprintf_P(cmd, PSTR("G0 F300 Z%s"), dtostrf(Z_CLEARANCE_BETWEEN_PROBES, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); - sprintf_P(cmd, PSTR("G42 F4000 I%i J%i"), mesh_x, mesh_y); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - current_position.z = goto_mesh_value ? Z_VALUES_ARR[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; - planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); - planner.synchronize(); - CrealityDWIN.Redraw_Menu(); - } - } - - float get_max_value() { - float max = __FLT_MIN__; - GRID_LOOP(x, y) { - if (!isnan(Z_VALUES_ARR[x][y]) && Z_VALUES_ARR[x][y] > max) - max = Z_VALUES_ARR[x][y]; - } - return max; - } - - float get_min_value() { - float min = __FLT_MAX__; - GRID_LOOP(x, y) { - if (!isnan(Z_VALUES_ARR[x][y]) && Z_VALUES_ARR[x][y] < min) - min = Z_VALUES_ARR[x][y]; - } - return min; - } - - void Draw_Bed_Mesh(int16_t selected = -1, uint8_t gridline_width = 1, uint16_t padding_x = 8, uint16_t padding_y_top = 40 + 53 - 7) { - drawing_mesh = true; - const uint16_t total_width_px = DWIN_WIDTH - padding_x - padding_x; - const uint16_t cell_width_px = total_width_px / GRID_MAX_POINTS_X; - const uint16_t cell_height_px = total_width_px / GRID_MAX_POINTS_Y; - const float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = _MAX(v_min, v_max); - - // Clear background from previous selection and select new square - DWIN_Draw_Rectangle(1, Color_Bg_Black, _MAX(0, padding_x - gridline_width), _MAX(0, padding_y_top - gridline_width), padding_x + total_width_px, padding_y_top + total_width_px); - if (selected >= 0) { - const auto selected_y = selected / GRID_MAX_POINTS_X; - const auto selected_x = selected - (GRID_MAX_POINTS_X * selected_y); - const auto start_y_px = padding_y_top + selected_y * cell_height_px; - const auto start_x_px = padding_x + selected_x * cell_width_px; - DWIN_Draw_Rectangle(1, Color_White, _MAX(0, start_x_px - gridline_width), _MAX(0, start_y_px - gridline_width), start_x_px + cell_width_px, start_y_px + cell_height_px); - } - - // Draw value square grid - char buf[8]; - GRID_LOOP(x, y) { - const auto start_x_px = padding_x + x * cell_width_px; - const auto end_x_px = start_x_px + cell_width_px - 1 - gridline_width; - const auto start_y_px = padding_y_top + (GRID_MAX_POINTS_Y - y - 1) * cell_height_px; - const auto end_y_px = start_y_px + cell_height_px - 1 - gridline_width; - DWIN_Draw_Rectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ - isnan(Z_VALUES_ARR[x][y]) ? Color_Grey : ( // gray if undefined - (Z_VALUES_ARR[x][y] < 0 ? - (uint16_t)round(0x1F * -Z_VALUES_ARR[x][y] / (!viewer_asymmetric_range ? range : v_min)) << 11 : // red if mesh point value is negative - (uint16_t)round(0x3F * Z_VALUES_ARR[x][y] / (!viewer_asymmetric_range ? range : v_max)) << 5) | // green if mesh point value is positive - _MIN(0x1F, (((uint8_t)abs(Z_VALUES_ARR[x][y]) / 10) * 4))), // + blue stepping for every mm - start_x_px, start_y_px, end_x_px, end_y_px - ); - - safe_delay(10); - LCD_SERIAL.flushTX(); - - // Draw value text on - if (viewer_print_value) { - int8_t offset_x, offset_y = cell_height_px / 2 - 6; - if (isnan(Z_VALUES_ARR[x][y])) { // undefined - DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); - } - else { // has value - if (GRID_MAX_POINTS_X < 10) - sprintf_P(buf, PSTR("%s"), dtostrf(abs(Z_VALUES_ARR[x][y]), 1, 2, str_1)); - else - sprintf_P(buf, PSTR("%02i"), (uint16_t)(abs(Z_VALUES_ARR[x][y] - (int16_t)Z_VALUES_ARR[x][y]) * 100)); - offset_x = cell_width_px / 2 - 3 * (strlen(buf)) - 2; - if (!(GRID_MAX_POINTS_X < 10)) - DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); - DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, buf); - } - safe_delay(10); - LCD_SERIAL.flushTX(); - } - } - } - - void Set_Mesh_Viewer_Status() { // TODO: draw gradient with values as a legend instead - float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = _MAX(v_min, v_max); - if (v_min > 3e+10F) v_min = 0.0000001; - if (v_max > 3e+10F) v_max = 0.0000001; - if (range > 3e+10F) range = 0.0000001; - char msg[46]; - if (viewer_asymmetric_range) { - dtostrf(-v_min, 1, 3, str_1); - dtostrf( v_max, 1, 3, str_2); - } - else { - dtostrf(-range, 1, 3, str_1); - dtostrf( range, 1, 3, str_2); - } - sprintf_P(msg, PSTR("Red %s..0..%s Green"), str_1, str_2); - CrealityDWIN.Update_Status(msg); - drawing_mesh = false; - } - - }; - Mesh_Settings mesh_conf; - -#endif // HAS_MESH - -/* General Display Functions */ - -struct CrealityDWINClass::EEPROM_Settings CrealityDWINClass::eeprom_settings{0}; -constexpr const char * const CrealityDWINClass::color_names[11]; -constexpr const char * const CrealityDWINClass::preheat_modes[3]; - -// Clear a part of the screen -// 4=Entire screen -// 3=Title bar and Menu area (default) -// 2=Menu area -// 1=Title bar -void CrealityDWINClass::Clear_Screen(uint8_t e/*=3*/) { - if (e == 1 || e == 3 || e == 4) DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.menu_top_bg, Color_Bg_Blue, false), 0, 0, DWIN_WIDTH, TITLE_HEIGHT); // Clear Title Bar - if (e == 2 || e == 3) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, STATUS_Y); // Clear Menu Area - if (e == 4) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); // Clear Popup Area -} - -void CrealityDWINClass::Draw_Float(float value, uint8_t row, bool selected/*=false*/, uint8_t minunit/*=10*/) { - const uint8_t digits = (uint8_t)floor(log10(abs(value))) + log10(minunit) + (minunit > 1); - const uint16_t bColor = (selected) ? Select_Color : Color_Bg_Black; - const uint16_t xpos = 240 - (digits * 8); - DWIN_Draw_Rectangle(1, Color_Bg_Black, 194, MBASE(row), 234 - (digits * 8), MBASE(row) + 16); - if (isnan(value)) - DWIN_Draw_String(true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F(" NaN")); - else { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, Color_White, bColor, digits - log10(minunit) + 1, log10(minunit), xpos, MBASE(row), (value < 0 ? -value : value)); - DWIN_Draw_String(true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), value < 0 ? F("-") : F(" ")); - } -} - -void CrealityDWINClass::Draw_Option(uint8_t value, const char * const * options, uint8_t row, bool selected/*=false*/, bool color/*=false*/) { - uint16_t bColor = (selected) ? Select_Color : Color_Bg_Black; - uint16_t tColor = (color) ? GetColor(value, Color_White, false) : Color_White; - DWIN_Draw_Rectangle(1, bColor, 202, MBASE(row) + 14, 258, MBASE(row) - 2); - DWIN_Draw_String(false, DWIN_FONT_MENU, tColor, bColor, 202, MBASE(row) - 1, options[value]); -} - -uint16_t CrealityDWINClass::GetColor(uint8_t color, uint16_t original, bool light/*=false*/) { - switch (color){ - case Default: - return original; - break; - case White: - return (light) ? Color_Light_White : Color_White; - break; - case Green: - return (light) ? Color_Light_Green : Color_Green; - break; - case Cyan: - return (light) ? Color_Light_Cyan : Color_Cyan; - break; - case Blue: - return (light) ? Color_Light_Blue : Color_Blue; - break; - case Magenta: - return (light) ? Color_Light_Magenta : Color_Magenta; - break; - case Red: - return (light) ? Color_Light_Red : Color_Red; - break; - case Orange: - return (light) ? Color_Light_Orange : Color_Orange; - break; - case Yellow: - return (light) ? Color_Light_Yellow : Color_Yellow; - break; - case Brown: - return (light) ? Color_Light_Brown : Color_Brown; - break; - case Black: - return Color_Black; - break; - } - return Color_White; -} - -void CrealityDWINClass::Draw_Title(const char * ctitle) { - DWIN_Draw_String(false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen(ctitle) * STAT_CHR_W) / 2, 5, ctitle); -} -void CrealityDWINClass::Draw_Title(FSTR_P const ftitle) { - DWIN_Draw_String(false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen_P(FTOP(ftitle)) * STAT_CHR_W) / 2, 5, ftitle); -} - -void _Decorate_Menu_Item(uint8_t row, uint8_t icon, bool more) { - if (icon) DWIN_ICON_Show(ICON, icon, 26, MBASE(row) - 3); //Draw Menu Icon - if (more) DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(row) - 3); // Draw More Arrow - DWIN_Draw_Line(CrealityDWIN.GetColor(CrealityDWIN.eeprom_settings.menu_split_line, Line_Color, true), 16, MBASE(row) + 33, 256, MBASE(row) + 33); // Draw Menu Line -} - -void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, const char * label1, const char * label2, bool more/*=false*/, bool centered/*=false*/) { - const uint8_t label_offset_y = (label1 || label2) ? MENU_CHR_H * 3 / 5 : 0, - label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2), - label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); - if (label1) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, label1); // Draw Label - if (label2) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, label2); // Draw Label - _Decorate_Menu_Item(row, icon, more); -} - -void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, FSTR_P const flabel1, FSTR_P const flabel2, bool more/*=false*/, bool centered/*=false*/) { - const uint8_t label_offset_y = (flabel1 || flabel2) ? MENU_CHR_H * 3 / 5 : 0, - label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (flabel1 ? strlen_P(FTOP(flabel1)) : 0) * MENU_CHR_W) / 2), - label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (flabel2 ? strlen_P(FTOP(flabel2)) : 0) * MENU_CHR_W) / 2); - if (flabel1) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, flabel1); // Draw Label - if (flabel2) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, flabel2); // Draw Label - _Decorate_Menu_Item(row, icon, more); -} - -void CrealityDWINClass::Draw_Checkbox(uint8_t row, bool value) { - #if ENABLED(DWIN_CREALITY_LCD_CUSTOM_ICONS) // Draw appropriate checkbox icon - DWIN_ICON_Show(ICON, (value ? ICON_Checkbox_T : ICON_Checkbox_F), 226, MBASE(row) - 3); - #else // Draw a basic checkbox using rectangles and lines - DWIN_Draw_Rectangle(1, Color_Bg_Black, 226, MBASE(row) - 3, 226 + 20, MBASE(row) - 3 + 20); - DWIN_Draw_Rectangle(0, Color_White, 226, MBASE(row) - 3, 226 + 20, MBASE(row) - 3 + 20); - if (value) { - DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 11, 226 + 8, MBASE(row) - 3 + 17); - DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 17, 226 + 19, MBASE(row) - 3 + 1); - DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 12, 226 + 8, MBASE(row) - 3 + 18); - DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 18, 226 + 19, MBASE(row) - 3 + 2); - DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 13, 226 + 8, MBASE(row) - 3 + 19); - DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 19, 226 + 19, MBASE(row) - 3 + 3); - } - #endif -} - -void CrealityDWINClass::Draw_Menu(uint8_t menu, uint8_t select/*=0*/, uint8_t scroll/*=0*/) { - if (active_menu != menu) { - last_menu = active_menu; - if (process == Menu) last_selection = selection; - } - selection = _MIN(select, Get_Menu_Size(menu)); - scrollpos = scroll; - if (selection - scrollpos > MROWS) - scrollpos = selection - MROWS; - process = Menu; - active_menu = menu; - Clear_Screen(); - Draw_Title(Get_Menu_Title(menu)); - LOOP_L_N(i, TROWS) Menu_Item_Handler(menu, i + scrollpos); - DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); -} - -void CrealityDWINClass::Redraw_Menu(bool lastprocess/*=true*/, bool lastselection/*=false*/, bool lastmenu/*=false*/) { - switch ((lastprocess) ? last_process : process) { - case Menu: - Draw_Menu((lastmenu) ? last_menu : active_menu, (lastselection) ? last_selection : selection, (lastmenu) ? 0 : scrollpos); - break; - case Main: Draw_Main_Menu((lastselection) ? last_selection : selection); break; - case Print: Draw_Print_Screen(); break; - case File: Draw_SD_List(); break; - default: break; - } -} - -void CrealityDWINClass::Redraw_Screen() { - Redraw_Menu(false); - Draw_Status_Area(true); - Update_Status_Bar(true); -} - -/* Primary Menus and Screen Elements */ - -void CrealityDWINClass::Main_Menu_Icons() { - if (selection == 0) { - DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 17, 130, 126, 229); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); - } - else { - DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); - } - if (selection == 1) { - DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 130, 254, 229); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); - } - else { - DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); - } - if (selection == 2) { - DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 17, 246, 126, 345); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); - } - else { - DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); - } - #if HAS_ABL_OR_UBL - if (selection == 3) { - DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 246, 254, 345); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); - } - else { - DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); - } - #else - if (selection == 3) { - DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 246, 254, 345); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); - } - else { - DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); - } - #endif -} - -void CrealityDWINClass::Draw_Main_Menu(uint8_t select/*=0*/) { - process = Main; - active_menu = MainMenu; - selection = select; - Clear_Screen(); - Draw_Title(Get_Menu_Title(MainMenu)); - SERIAL_ECHOPGM("\nDWIN handshake "); - DWIN_ICON_Show(ICON, ICON_LOGO, 71, 72); - Main_Menu_Icons(); -} - -void CrealityDWINClass::Print_Screen_Icons() { - if (selection == 0) { - DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 8, 252, 87, 351); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); - } - else { - DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); - } - if (selection == 2) { - DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 184, 252, 263, 351); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); - } - else { - DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); - } - if (paused) { - if (selection == 1) { - DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 96, 252, 175, 351); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); - } - else { - DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); - } - } - else { - if (selection == 1) { - DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 96, 252, 175, 351); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); - } - else { - DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); - } - } -} - -void CrealityDWINClass::Draw_Print_Screen() { - process = Print; - selection = 0; - Clear_Screen(); - DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); - Draw_Title("Printing..."); - Print_Screen_Icons(); - DWIN_ICON_Show(ICON, ICON_PrintTime, 14, 171); - DWIN_ICON_Show(ICON, ICON_RemainTime, 147, 169); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 41, 163, F("Elapsed")); - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 176, 163, F("Remaining")); - Update_Status_Bar(true); - Draw_Print_ProgressBar(); - Draw_Print_ProgressElapsed(); - TERN_(USE_M73_REMAINING_TIME, Draw_Print_ProgressRemain()); - Draw_Print_Filename(true); -} - -void CrealityDWINClass::Draw_Print_Filename(const bool reset/*=false*/) { - static uint8_t namescrl = 0; - if (reset) namescrl = 0; - if (process == Print) { - constexpr int8_t maxlen = 30; - char *outstr = filename; - size_t slen = strlen(filename); - int8_t outlen = slen; - if (slen > maxlen) { - char dispname[maxlen + 1]; - int8_t pos = slen - namescrl, len = maxlen; - if (pos >= 0) { - NOMORE(len, pos); - LOOP_L_N(i, len) dispname[i] = filename[i + namescrl]; - } - else { - const int8_t mp = maxlen + pos; - LOOP_L_N(i, mp) dispname[i] = ' '; - LOOP_S_L_N(i, mp, maxlen) dispname[i] = filename[i - mp]; - if (mp <= 0) namescrl = 0; - } - dispname[len] = '\0'; - outstr = dispname; - outlen = maxlen; - namescrl++; - } - DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); - const int8_t npos = (DWIN_WIDTH - outlen * MENU_CHR_W) / 2; - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, outstr); - } -} - -void CrealityDWINClass::Draw_Print_ProgressBar() { - uint8_t printpercent = sdprint ? card.percentDone() : (ui._get_progress() / 100); - DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); - DWIN_Draw_Rectangle(1, BarFill_Color, 16 + printpercent * 240 / 100, 93, 256, 113); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 3, 109, 133, printpercent); - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 133, 133, F("%")); -} - -#if ENABLED(USE_M73_REMAINING_TIME) - - void CrealityDWINClass::Draw_Print_ProgressRemain() { - uint16_t remainingtime = ui.get_remaining_time(); - DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 176, 187, remainingtime / 3600); - DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 200, 187, (remainingtime % 3600) / 60); - if (eeprom_settings.time_format_textual) { - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, F("h")); - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 216, 187, F("m")); - } - else - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, F(":")); - } - -#endif - -void CrealityDWINClass::Draw_Print_ProgressElapsed() { - duration_t elapsed = print_job_timer.duration(); - DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 42, 187, elapsed.value / 3600); - DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 66, 187, (elapsed.value % 3600) / 60); - if (eeprom_settings.time_format_textual) { - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, F("h")); - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 82, 187, F("m")); - } - else - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, F(":")); -} - -void CrealityDWINClass::Draw_Print_confirm() { - Draw_Print_Screen(); - process = Confirm; - popup = Complete; - DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 252, 263, 351); - DWIN_ICON_Show(ICON, ICON_Confirm_E, 87, 283); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 86, 282, 187, 321); - DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 85, 281, 188, 322); -} - -void CrealityDWINClass::Draw_SD_Item(uint8_t item, uint8_t row) { - if (item == 0) - Draw_Menu_Item(0, ICON_Back, card.flag.workDirIsRoot ? F("Back") : F("..")); - else { - card.getfilename_sorted(SD_ORDER(item - 1, card.get_num_Files())); - char * const filename = card.longest_filename(); - size_t max = MENU_CHAR_LIMIT; - size_t pos = strlen(filename), len = pos; - if (!card.flag.filenameIsDir) - while (pos && filename[pos] != '.') pos--; - len = pos; - if (len > max) len = max; - char name[len + 1]; - LOOP_L_N(i, len) name[i] = filename[i]; - if (pos > max) - LOOP_S_L_N(i, len - 3, len) name[i] = '.'; - name[len] = '\0'; - Draw_Menu_Item(row, card.flag.filenameIsDir ? ICON_More : ICON_File, name); - } -} - -void CrealityDWINClass::Draw_SD_List(bool removed/*=false*/) { - Clear_Screen(); - Draw_Title("Select File"); - selection = 0; - scrollpos = 0; - process = File; - if (card.isMounted() && !removed) { - LOOP_L_N(i, _MIN(card.get_num_Files() + 1, TROWS)) - Draw_SD_Item(i, i); - } - else { - Draw_Menu_Item(0, ICON_Back, F("Back")); - 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")); - } - DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(0) - 18, 14, MBASE(0) + 33); -} - -void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { - - if (icons) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); - - #if HAS_HOTEND - static float hotend = -1; - static int16_t hotendtarget = -1, flow = -1; - if (icons) { - hotend = -1; - hotendtarget = -1; - DWIN_ICON_Show(ICON, ICON_HotendTemp, 10, 383); - DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); - } - if (thermalManager.temp_hotend[0].celsius != hotend) { - hotend = thermalManager.temp_hotend[0].celsius; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 28, 384, thermalManager.temp_hotend[0].celsius); - DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 3 * STAT_CHR_W + 5, 386); - } - if (thermalManager.temp_hotend[0].target != hotendtarget) { - hotendtarget = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 384, thermalManager.temp_hotend[0].target); - DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 4 * STAT_CHR_W + 39, 386); - } - if (icons) { - flow = -1; - DWIN_ICON_Show(ICON, ICON_StepE, 112, 417); - DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); - } - if (planner.flow_percentage[0] != flow) { - flow = planner.flow_percentage[0]; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 417, planner.flow_percentage[0]); - } - #endif - - #if HAS_HEATED_BED - static float bed = -1; - static int16_t bedtarget = -1; - if (icons) { - bed = -1; - bedtarget = -1; - DWIN_ICON_Show(ICON, ICON_BedTemp, 10, 416); - DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); - } - if (thermalManager.temp_bed.celsius != bed) { - bed = thermalManager.temp_bed.celsius; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 28, 417, thermalManager.temp_bed.celsius); - DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 3 * STAT_CHR_W + 5, 419); - } - if (thermalManager.temp_bed.target != bedtarget) { - bedtarget = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.temp_bed.target); - DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 4 * STAT_CHR_W + 39, 419); - } - #endif - - #if HAS_FAN - static uint8_t fan = -1; - if (icons) { - fan = -1; - DWIN_ICON_Show(ICON, ICON_FanSpeed, 187, 383); - } - if (thermalManager.fan_speed[0] != fan) { - fan = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 195 + 2 * STAT_CHR_W, 384, thermalManager.fan_speed[0]); - } - #endif - - #if HAS_ZOFFSET_ITEM - static float offset = -1; - - if (icons) { - offset = -1; - DWIN_ICON_Show(ICON, ICON_Zoffset, 187, 416); - } - if (zoffsetvalue != offset) { - offset = zoffsetvalue; - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 2, 2, 207, 417, (zoffsetvalue < 0 ? -zoffsetvalue : zoffsetvalue)); - DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 205, 419, zoffsetvalue < 0 ? F("-") : F(" ")); - } - #endif - - static int16_t feedrate = -1; - if (icons) { - feedrate = -1; - DWIN_ICON_Show(ICON, ICON_Speed, 113, 383); - DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); - } - if (feedrate_percentage != feedrate) { - feedrate = feedrate_percentage; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 384, feedrate_percentage); - } - - static float x = -1, y = -1, z = -1; - static bool update_x = false, update_y = false, update_z = false; - update_x = (current_position.x != x || axis_should_home(X_AXIS) || update_x); - update_y = (current_position.y != y || axis_should_home(Y_AXIS) || update_y); - update_z = (current_position.z != z || axis_should_home(Z_AXIS) || update_z); - if (icons) { - x = y = z = -1; - DWIN_Draw_Line(GetColor(eeprom_settings.coordinates_split_line, Line_Color, true), 16, 450, 256, 450); - DWIN_ICON_Show(ICON, ICON_MaxSpeedX, 10, 456); - DWIN_ICON_Show(ICON, ICON_MaxSpeedY, 95, 456); - DWIN_ICON_Show(ICON, ICON_MaxSpeedZ, 180, 456); - } - if (update_x) { - x = current_position.x; - if ((update_x = axis_should_home(X_AXIS) && ui.get_blink())) - DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 35, 459, F(" -?- ")); - else - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 1, 35, 459, current_position.x); - } - if (update_y) { - y = current_position.y; - if ((update_y = axis_should_home(Y_AXIS) && ui.get_blink())) - DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 120, 459, F(" -?- ")); - else - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 1, 120, 459, current_position.y); - } - if (update_z) { - z = current_position.z; - if ((update_z = axis_should_home(Z_AXIS) && ui.get_blink())) - DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 205, 459, F(" -?- ")); - else - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 2, 205, 459, (current_position.z>=0) ? current_position.z : 0); - } - DWIN_UpdateLCD(); -} - -void CrealityDWINClass::Draw_Popup(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, uint8_t mode, uint8_t icon/*=0*/) { - if (process != Confirm && process != Popup && process != Wait) last_process = process; - if ((process == Menu || process == Wait) && mode == Popup) last_selection = selection; - process = mode; - Clear_Screen(); - DWIN_Draw_Rectangle(0, Color_White, 13, 59, 259, 351); - DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 350); - const uint8_t ypos = (mode == Popup || mode == Confirm) ? 150 : 230; - if (icon > 0) DWIN_ICON_Show(ICON, icon, 101, 105); - DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line1))) / 2, ypos, line1); - DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line2))) / 2, ypos + 30, line2); - DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line3))) / 2, ypos + 60, line3); - if (mode == Popup) { - selection = 0; - DWIN_Draw_Rectangle(1, Confirm_Color, 26, 280, 125, 317); - DWIN_Draw_Rectangle(1, Cancel_Color, 146, 280, 245, 317); - DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 39, 290, F("Confirm")); - DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 165, 290, F("Cancel")); - Popup_Select(); - } - else if (mode == Confirm) { - DWIN_Draw_Rectangle(1, Confirm_Color, 87, 280, 186, 317); - DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 96, 290, F("Continue")); - } -} - -void MarlinUI::kill_screen(FSTR_P const error, FSTR_P const) { - CrealityDWIN.Draw_Popup(F("Printer Kill Reason:"), error, F("Restart Required"), Wait, ICON_BLTouch); -} - -void CrealityDWINClass::Popup_Select() { - const uint16_t c1 = (selection == 0) ? GetColor(eeprom_settings.highlight_box, Color_White) : Color_Bg_Window, - c2 = (selection == 0) ? Color_Bg_Window : GetColor(eeprom_settings.highlight_box, Color_White); - 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 CrealityDWINClass::Update_Status_Bar(bool refresh/*=false*/) { - static bool new_msg; - static uint8_t msgscrl = 0; - static char lastmsg[64]; - if (strcmp(lastmsg, statusmsg) != 0 || refresh) { - strcpy(lastmsg, statusmsg); - msgscrl = 0; - new_msg = true; - } - size_t len = strlen(statusmsg); - int8_t pos = len; - if (pos > 30) { - pos -= msgscrl; - len = pos; - if (len > 30) - len = 30; - char dispmsg[len + 1]; - if (pos >= 0) { - LOOP_L_N(i, len) dispmsg[i] = statusmsg[i + msgscrl]; - } - else { - LOOP_L_N(i, 30 + pos) dispmsg[i] = ' '; - LOOP_S_L_N(i, 30 + pos, 30) dispmsg[i] = statusmsg[i - (30 + pos)]; - } - dispmsg[len] = '\0'; - if (process == Print) { - DWIN_Draw_Rectangle(1, Color_Grey, 8, 214, DWIN_WIDTH - 8, 238); - const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, dispmsg); - } - else { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); - const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, dispmsg); - } - if (-pos >= 30) msgscrl = 0; - msgscrl++; - } - else { - if (new_msg) { - new_msg = false; - if (process == Print) { - DWIN_Draw_Rectangle(1, Color_Grey, 8, 214, DWIN_WIDTH - 8, 238); - const int8_t npos = (DWIN_WIDTH - strlen(statusmsg) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, statusmsg); - } - else { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); - const int8_t npos = (DWIN_WIDTH - strlen(statusmsg) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, statusmsg); - } - } - } -} - -/* Menu Item Config */ - -void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/*=true*/) { - const uint8_t row = item - scrollpos; - #if HAS_LEVELING - static bool level_state; - #endif - - #if HAS_PREHEAT - - #define PREHEAT_BACK 0 - #define PREHEAT_SUBMENU_HOTEND (PREHEAT_BACK + ENABLED(HAS_HOTEND)) - #define PREHEAT_SUBMENU_BED (PREHEAT_SUBMENU_HOTEND + ENABLED(HAS_HEATED_BED)) - #define PREHEAT_SUBMENU_FAN (PREHEAT_SUBMENU_BED + ENABLED(HAS_FAN)) - #define PREHEAT_SUBMENU_TOTAL PREHEAT_SUBMENU_FAN - - auto preheat_submenu = [&](const int index, const uint8_t item, const uint8_t sel) { - switch (item) { - case PREHEAT_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(TempMenu, sel); - break; - #if HAS_HOTEND - case PREHEAT_SUBMENU_HOTEND: - if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); - Draw_Float(ui.material_preset[index].hotend_temp, row, false, 1); - } - else - Modify_Value(ui.material_preset[index].hotend_temp, MIN_E_TEMP, MAX_E_TEMP, 1); - break; - #endif - #if HAS_HEATED_BED - case PREHEAT_SUBMENU_BED: - if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); - Draw_Float(ui.material_preset[index].bed_temp, row, false, 1); - } - else - Modify_Value(ui.material_preset[index].bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); - break; - #endif - #if HAS_FAN - case PREHEAT_SUBMENU_FAN: - if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); - Draw_Float(ui.material_preset[index].fan_speed, row, false, 1); - } - else - Modify_Value(ui.material_preset[index].fan_speed, MIN_FAN_SPEED, MAX_FAN_SPEED, 1); - break; - #endif - } - }; - - #endif - - switch (menu) { - case Prepare: - - #define PREPARE_BACK 0 - #define PREPARE_MOVE (PREPARE_BACK + 1) - #define PREPARE_DISABLE (PREPARE_MOVE + 1) - #define PREPARE_HOME (PREPARE_DISABLE + 1) - #define PREPARE_MANUALLEVEL (PREPARE_HOME + 1) - #define PREPARE_ZOFFSET (PREPARE_MANUALLEVEL + ENABLED(HAS_ZOFFSET_ITEM)) - #define PREPARE_PREHEAT (PREPARE_ZOFFSET + ENABLED(HAS_PREHEAT)) - #define PREPARE_COOLDOWN (PREPARE_PREHEAT + EITHER(HAS_HOTEND, HAS_HEATED_BED)) - #define PREPARE_CHANGEFIL (PREPARE_COOLDOWN + ENABLED(ADVANCED_PAUSE_FEATURE)) - #define PREPARE_TOTAL PREPARE_CHANGEFIL - - switch (item) { - case PREPARE_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Main_Menu(1); - break; - case PREPARE_MOVE: - if (draw) - Draw_Menu_Item(row, ICON_Axis, F("Move"), nullptr, true); - else - Draw_Menu(Move); - break; - case PREPARE_DISABLE: - if (draw) - Draw_Menu_Item(row, ICON_CloseMotor, F("Disable Stepper")); - else - queue.inject(F("M84")); - break; - case PREPARE_HOME: - if (draw) - Draw_Menu_Item(row, ICON_SetHome, F("Homing"), nullptr, true); - else - Draw_Menu(HomeMenu); - break; - case PREPARE_MANUALLEVEL: - if (draw) - Draw_Menu_Item(row, ICON_PrintSize, F("Manual Leveling"), nullptr, true); - else { - if (axes_should_home()) { - Popup_Handler(Home); - gcode.home_all_axes(true); - } - #if HAS_LEVELING - level_state = planner.leveling_active; - set_bed_leveling_enabled(false); - #endif - Draw_Menu(ManualLevel); - } - break; - - #if HAS_ZOFFSET_ITEM - case PREPARE_ZOFFSET: - if (draw) - Draw_Menu_Item(row, ICON_Zoffset, F("Z-Offset"), nullptr, true); - else { - #if HAS_LEVELING - level_state = planner.leveling_active; - set_bed_leveling_enabled(false); - #endif - Draw_Menu(ZOffset); - } - break; - #endif - - #if HAS_PREHEAT - case PREPARE_PREHEAT: - if (draw) - Draw_Menu_Item(row, ICON_Temperature, F("Preheat"), nullptr, true); - else - Draw_Menu(Preheat); - break; - #endif - - #if HAS_HOTEND || HAS_HEATED_BED - case PREPARE_COOLDOWN: - if (draw) - Draw_Menu_Item(row, ICON_Cool, F("Cooldown")); - else - thermalManager.cooldown(); - break; - #endif - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - case PREPARE_CHANGEFIL: - if (draw) { - Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament") - #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - , nullptr, true - #endif - ); - } - else { - #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - Draw_Menu(ChangeFilament); - #else - if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) - Popup_Handler(ETemp); - else { - if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { - Popup_Handler(Heating); - thermalManager.wait_for_hotend(0); - } - Popup_Handler(FilChange); - sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now(cmd); - } - #endif - } - break; - #endif - } - break; - - case HomeMenu: - - #define HOME_BACK 0 - #define HOME_ALL (HOME_BACK + 1) - #define HOME_X (HOME_ALL + 1) - #define HOME_Y (HOME_X + 1) - #define HOME_Z (HOME_Y + 1) - #define HOME_SET (HOME_Z + 1) - #define HOME_TOTAL HOME_SET - - switch (item) { - case HOME_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Prepare, PREPARE_HOME); - break; - case HOME_ALL: - if (draw) - Draw_Menu_Item(row, ICON_Homing, F("Home All")); - else { - Popup_Handler(Home); - gcode.home_all_axes(true); - Redraw_Menu(); - } - break; - case HOME_X: - if (draw) - Draw_Menu_Item(row, ICON_MoveX, F("Home X")); - else { - Popup_Handler(Home); - gcode.process_subcommands_now(F("G28 X")); - planner.synchronize(); - Redraw_Menu(); - } - break; - case HOME_Y: - if (draw) - Draw_Menu_Item(row, ICON_MoveY, F("Home Y")); - else { - Popup_Handler(Home); - gcode.process_subcommands_now(F("G28 Y")); - planner.synchronize(); - Redraw_Menu(); - } - break; - case HOME_Z: - if (draw) - Draw_Menu_Item(row, ICON_MoveZ, F("Home Z")); - else { - Popup_Handler(Home); - gcode.process_subcommands_now(F("G28 Z")); - planner.synchronize(); - Redraw_Menu(); - } - break; - case HOME_SET: - if (draw) - Draw_Menu_Item(row, ICON_SetHome, F("Set Home Position")); - else { - gcode.process_subcommands_now(F("G92 X0 Y0 Z0")); - AudioFeedback(); - } - break; - } - break; - - case Move: - - #define MOVE_BACK 0 - #define MOVE_X (MOVE_BACK + 1) - #define MOVE_Y (MOVE_X + 1) - #define MOVE_Z (MOVE_Y + 1) - #define MOVE_E (MOVE_Z + ENABLED(HAS_HOTEND)) - #define MOVE_P (MOVE_E + ENABLED(HAS_BED_PROBE)) - #define MOVE_LIVE (MOVE_P + 1) - #define MOVE_TOTAL MOVE_LIVE - - switch (item) { - case MOVE_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else { - #if HAS_BED_PROBE - probe_deployed = false; - probe.set_deployed(probe_deployed); - #endif - Draw_Menu(Prepare, PREPARE_MOVE); - } - break; - case MOVE_X: - if (draw) { - Draw_Menu_Item(row, ICON_MoveX, F("Move X")); - Draw_Float(current_position.x, row, false); - } - else - Modify_Value(current_position.x, X_MIN_POS, X_MAX_POS, 10); - break; - case MOVE_Y: - if (draw) { - Draw_Menu_Item(row, ICON_MoveY, F("Move Y")); - Draw_Float(current_position.y, row); - } - else - Modify_Value(current_position.y, Y_MIN_POS, Y_MAX_POS, 10); - break; - case MOVE_Z: - if (draw) { - Draw_Menu_Item(row, ICON_MoveZ, F("Move Z")); - Draw_Float(current_position.z, row); - } - else - Modify_Value(current_position.z, Z_MIN_POS, Z_MAX_POS, 10); - break; - - #if HAS_HOTEND - case MOVE_E: - if (draw) { - Draw_Menu_Item(row, ICON_Extruder, F("Extruder")); - current_position.e = 0; - sync_plan_position(); - Draw_Float(current_position.e, row); - } - else { - if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) { - Popup_Handler(ETemp); - } - else { - if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { - Popup_Handler(Heating); - thermalManager.wait_for_hotend(0); - Redraw_Menu(); - } - current_position.e = 0; - sync_plan_position(); - Modify_Value(current_position.e, -500, 500, 10); - } - } - break; - #endif // HAS_HOTEND - - #if HAS_BED_PROBE - case MOVE_P: - if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguration, F("Probe")); - Draw_Checkbox(row, probe_deployed); - } - else { - probe_deployed = !probe_deployed; - probe.set_deployed(probe_deployed); - Draw_Checkbox(row, probe_deployed); - } - break; - #endif - - case MOVE_LIVE: - if (draw) { - Draw_Menu_Item(row, ICON_Axis, F("Live Movement")); - Draw_Checkbox(row, livemove); - } - else { - livemove = !livemove; - Draw_Checkbox(row, livemove); - } - break; - } - break; - case ManualLevel: - - #define MLEVEL_BACK 0 - #define MLEVEL_PROBE (MLEVEL_BACK + ENABLED(HAS_BED_PROBE)) - #define MLEVEL_BL (MLEVEL_PROBE + 1) - #define MLEVEL_TL (MLEVEL_BL + 1) - #define MLEVEL_TR (MLEVEL_TL + 1) - #define MLEVEL_BR (MLEVEL_TR + 1) - #define MLEVEL_C (MLEVEL_BR + 1) - #define MLEVEL_ZPOS (MLEVEL_C + 1) - #define MLEVEL_TOTAL MLEVEL_ZPOS - - static float mlev_z_pos = 0; - static bool use_probe = false; - - switch (item) { - case MLEVEL_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else { - TERN_(HAS_LEVELING, set_bed_leveling_enabled(level_state)); - Draw_Menu(Prepare, PREPARE_MANUALLEVEL); - } - break; - #if HAS_BED_PROBE - case MLEVEL_PROBE: - if (draw) { - Draw_Menu_Item(row, ICON_Zoffset, F("Use Probe")); - Draw_Checkbox(row, use_probe); - } - else { - use_probe = !use_probe; - Draw_Checkbox(row, use_probe); - if (use_probe) { - Popup_Handler(Level); - corner_avg = 0; - #define PROBE_X_MIN _MAX(0 + corner_pos, X_MIN_POS + probe.offset.x, X_MIN_POS + PROBING_MARGIN) - probe.offset.x - #define PROBE_X_MAX _MIN((X_BED_SIZE + X_MIN_POS) - corner_pos, X_MAX_POS + probe.offset.x, X_MAX_POS - PROBING_MARGIN) - probe.offset.x - #define PROBE_Y_MIN _MAX(0 + corner_pos, Y_MIN_POS + probe.offset.y, Y_MIN_POS + PROBING_MARGIN) - probe.offset.y - #define PROBE_Y_MAX _MIN((Y_BED_SIZE + Y_MIN_POS) - corner_pos, Y_MAX_POS + probe.offset.y, Y_MAX_POS - PROBING_MARGIN) - probe.offset.y - corner_avg += probe.probe_at_point(PROBE_X_MIN, PROBE_Y_MIN, PROBE_PT_RAISE, 0, false); - corner_avg += probe.probe_at_point(PROBE_X_MIN, PROBE_Y_MAX, PROBE_PT_RAISE, 0, false); - corner_avg += probe.probe_at_point(PROBE_X_MAX, PROBE_Y_MAX, PROBE_PT_RAISE, 0, false); - corner_avg += probe.probe_at_point(PROBE_X_MAX, PROBE_Y_MIN, PROBE_PT_STOW, 0, false); - corner_avg /= 4; - Redraw_Menu(); - } - } - break; - #endif - case MLEVEL_BL: - if (draw) - Draw_Menu_Item(row, ICON_AxisBL, F("Bottom Left")); - else { - Popup_Handler(MoveWait); - if (use_probe) { - #if HAS_BED_PROBE - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MIN, 1, 3, str_1), dtostrf(PROBE_Y_MIN, 1, 3, str_2)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Popup_Handler(ManualProbing); - #endif - } - else { - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf(corner_pos, 1, 3, str_1), dtostrf(corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Redraw_Menu(); - } - } - break; - case MLEVEL_TL: - if (draw) - Draw_Menu_Item(row, ICON_AxisTL, F("Top Left")); - else { - Popup_Handler(MoveWait); - if (use_probe) { - #if HAS_BED_PROBE - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MIN, 1, 3, str_1), dtostrf(PROBE_Y_MAX, 1, 3, str_2)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Popup_Handler(ManualProbing); - #endif - } - else { - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf(corner_pos, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) - corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Redraw_Menu(); - } - } - break; - case MLEVEL_TR: - if (draw) - Draw_Menu_Item(row, ICON_AxisTR, F("Top Right")); - else { - Popup_Handler(MoveWait); - if (use_probe) { - #if HAS_BED_PROBE - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MAX, 1, 3, str_1), dtostrf(PROBE_Y_MAX, 1, 3, str_2)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Popup_Handler(ManualProbing); - #endif - } - else { - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) - corner_pos, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) - corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Redraw_Menu(); - } - } - break; - case MLEVEL_BR: - if (draw) - Draw_Menu_Item(row, ICON_AxisBR, F("Bottom Right")); - else { - Popup_Handler(MoveWait); - if (use_probe) { - #if HAS_BED_PROBE - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MAX, 1, 3, str_1), dtostrf(PROBE_Y_MIN, 1, 3, str_2)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Popup_Handler(ManualProbing); - #endif - } - else { - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) - corner_pos, 1, 3, str_1), dtostrf(corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Redraw_Menu(); - } - } - break; - case MLEVEL_C: - if (draw) - Draw_Menu_Item(row, ICON_AxisC, F("Center")); - else { - Popup_Handler(MoveWait); - if (use_probe) { - #if HAS_BED_PROBE - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(X_MAX_POS / 2.0f - probe.offset.x, 1, 3, str_1), dtostrf(Y_MAX_POS / 2.0f - probe.offset.y, 1, 3, str_2)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Popup_Handler(ManualProbing); - #endif - } - else { - sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Redraw_Menu(); - } - } - break; - case MLEVEL_ZPOS: - if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, F("Z Position")); - Draw_Float(mlev_z_pos, row, false, 100); - } - else - Modify_Value(mlev_z_pos, 0, MAX_Z_OFFSET, 100); - break; - } - break; - #if HAS_ZOFFSET_ITEM - case ZOffset: - - #define ZOFFSET_BACK 0 - #define ZOFFSET_HOME (ZOFFSET_BACK + 1) - #define ZOFFSET_MODE (ZOFFSET_HOME + 1) - #define ZOFFSET_OFFSET (ZOFFSET_MODE + 1) - #define ZOFFSET_UP (ZOFFSET_OFFSET + 1) - #define ZOFFSET_DOWN (ZOFFSET_UP + 1) - #define ZOFFSET_SAVE (ZOFFSET_DOWN + ENABLED(EEPROM_SETTINGS)) - #define ZOFFSET_TOTAL ZOFFSET_SAVE - - switch (item) { - case ZOFFSET_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else { - liveadjust = false; - TERN_(HAS_LEVELING, set_bed_leveling_enabled(level_state)); - Draw_Menu(Prepare, PREPARE_ZOFFSET); - } - break; - case ZOFFSET_HOME: - if (draw) - Draw_Menu_Item(row, ICON_Homing, F("Home Z Axis")); - else { - Popup_Handler(Home); - gcode.process_subcommands_now(F("G28 Z")); - Popup_Handler(MoveWait); - #if ENABLED(Z_SAFE_HOMING) - planner.synchronize(); - sprintf_P(cmd, PSTR("G0 F4000 X%s Y%s"), dtostrf(Z_SAFE_HOMING_X_POINT, 1, 3, str_1), dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 3, str_2)); - gcode.process_subcommands_now(cmd); - #else - gcode.process_subcommands_now(F("G0 F4000 X117.5 Y117.5")); - #endif - gcode.process_subcommands_now(F("G0 F300 Z0")); - planner.synchronize(); - Redraw_Menu(); - } - break; - case ZOFFSET_MODE: - if (draw) { - Draw_Menu_Item(row, ICON_Zoffset, F("Live Adjustment")); - Draw_Checkbox(row, liveadjust); - } - else { - if (!liveadjust) { - if (axes_should_home()) { - Popup_Handler(Home); - gcode.home_all_axes(true); - } - Popup_Handler(MoveWait); - #if ENABLED(Z_SAFE_HOMING) - planner.synchronize(); - sprintf_P(cmd, PSTR("G0 F4000 X%s Y%s"), dtostrf(Z_SAFE_HOMING_X_POINT, 1, 3, str_1), dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 3, str_2)); - gcode.process_subcommands_now(cmd); - #else - gcode.process_subcommands_now(F("G0 F4000 X117.5 Y117.5")); - #endif - gcode.process_subcommands_now(F("G0 F300 Z0")); - planner.synchronize(); - Redraw_Menu(); - } - liveadjust = !liveadjust; - Draw_Checkbox(row, liveadjust); - } - break; - case ZOFFSET_OFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, F("Z Offset")); - Draw_Float(zoffsetvalue, row, false, 100); - } - else - Modify_Value(zoffsetvalue, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); - break; - case ZOFFSET_UP: - if (draw) - Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); - else { - if (zoffsetvalue < MAX_Z_OFFSET) { - if (liveadjust) { - gcode.process_subcommands_now(F("M290 Z0.01")); - planner.synchronize(); - } - zoffsetvalue += 0.01; - Draw_Float(zoffsetvalue, row - 1, false, 100); - } - } - break; - case ZOFFSET_DOWN: - if (draw) - Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); - else { - if (zoffsetvalue > MIN_Z_OFFSET) { - if (liveadjust) { - gcode.process_subcommands_now(F("M290 Z-0.01")); - planner.synchronize(); - } - zoffsetvalue -= 0.01; - Draw_Float(zoffsetvalue, row - 2, false, 100); - } - } - break; - #if ENABLED(EEPROM_SETTINGS) - case ZOFFSET_SAVE: - if (draw) - Draw_Menu_Item(row, ICON_WriteEEPROM, F("Save")); - else - AudioFeedback(settings.save()); - break; - #endif - } - break; - #endif - - #if HAS_PREHEAT - case Preheat: { - #define PREHEAT_MODE (PREHEAT_BACK + 1) - #define PREHEAT_1 (PREHEAT_MODE + 1) - #define PREHEAT_2 (PREHEAT_1 + (PREHEAT_COUNT >= 2)) - #define PREHEAT_3 (PREHEAT_2 + (PREHEAT_COUNT >= 3)) - #define PREHEAT_4 (PREHEAT_3 + (PREHEAT_COUNT >= 4)) - #define PREHEAT_5 (PREHEAT_4 + (PREHEAT_COUNT >= 5)) - #define PREHEAT_TOTAL PREHEAT_5 - - auto do_preheat = [](const uint8_t m) { - thermalManager.cooldown(); - if (preheatmode == 0 || preheatmode == 1) { ui.preheat_hotend_and_fan(m); } - if (preheatmode == 0 || preheatmode == 2) ui.preheat_bed(m); - }; - - switch (item) { - case PREHEAT_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Prepare, PREPARE_PREHEAT); - break; - - case PREHEAT_MODE: - if (draw) { - Draw_Menu_Item(row, ICON_Homing, F("Preheat Mode")); - Draw_Option(preheatmode, preheat_modes, row); - } - else - Modify_Option(preheatmode, preheat_modes, 2); - break; - - #define _PREHEAT_CASE(N) \ - case PREHEAT_##N: { \ - if (draw) Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_## N ##_LABEL)); \ - else do_preheat(N - 1); \ - } break; - - REPEAT_1(PREHEAT_COUNT, _PREHEAT_CASE) - } - } break; - #endif // HAS_PREHEAT - - #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - case ChangeFilament: - - #define CHANGEFIL_BACK 0 - #define CHANGEFIL_LOAD (CHANGEFIL_BACK + 1) - #define CHANGEFIL_UNLOAD (CHANGEFIL_LOAD + 1) - #define CHANGEFIL_CHANGE (CHANGEFIL_UNLOAD + 1) - #define CHANGEFIL_TOTAL CHANGEFIL_CHANGE - - switch (item) { - case CHANGEFIL_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Prepare, PREPARE_CHANGEFIL); - break; - case CHANGEFIL_LOAD: - if (draw) - Draw_Menu_Item(row, ICON_WriteEEPROM, F("Load Filament")); - else { - if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) - Popup_Handler(ETemp); - else { - if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { - Popup_Handler(Heating); - thermalManager.wait_for_hotend(0); - } - Popup_Handler(FilLoad); - gcode.process_subcommands_now(F("M701")); - planner.synchronize(); - Redraw_Menu(); - } - } - break; - case CHANGEFIL_UNLOAD: - if (draw) - Draw_Menu_Item(row, ICON_ReadEEPROM, F("Unload Filament")); - else { - if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) { - Popup_Handler(ETemp); - } - else { - if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { - Popup_Handler(Heating); - thermalManager.wait_for_hotend(0); - } - Popup_Handler(FilLoad, true); - gcode.process_subcommands_now(F("M702")); - planner.synchronize(); - Redraw_Menu(); - } - } - break; - case CHANGEFIL_CHANGE: - if (draw) - Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament")); - else { - if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) - Popup_Handler(ETemp); - else { - if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { - Popup_Handler(Heating); - thermalManager.wait_for_hotend(0); - } - Popup_Handler(FilChange); - sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now(cmd); - } - } - break; - } - break; - #endif // FILAMENT_LOAD_UNLOAD_GCODES - - case Control: - - #define CONTROL_BACK 0 - #define CONTROL_TEMP (CONTROL_BACK + 1) - #define CONTROL_MOTION (CONTROL_TEMP + 1) - #define CONTROL_VISUAL (CONTROL_MOTION + 1) - #define CONTROL_ADVANCED (CONTROL_VISUAL + 1) - #define CONTROL_SAVE (CONTROL_ADVANCED + ENABLED(EEPROM_SETTINGS)) - #define CONTROL_RESTORE (CONTROL_SAVE + ENABLED(EEPROM_SETTINGS)) - #define CONTROL_RESET (CONTROL_RESTORE + ENABLED(EEPROM_SETTINGS)) - #define CONTROL_INFO (CONTROL_RESET + 1) - #define CONTROL_TOTAL CONTROL_INFO - - switch (item) { - case CONTROL_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Main_Menu(2); - break; - case CONTROL_TEMP: - if (draw) - Draw_Menu_Item(row, ICON_Temperature, F("Temperature"), nullptr, true); - else - Draw_Menu(TempMenu); - break; - case CONTROL_MOTION: - if (draw) - Draw_Menu_Item(row, ICON_Motion, F("Motion"), nullptr, true); - else - Draw_Menu(Motion); - break; - case CONTROL_VISUAL: - if (draw) - Draw_Menu_Item(row, ICON_PrintSize, F("Visual"), nullptr, true); - else - Draw_Menu(Visual); - break; - case CONTROL_ADVANCED: - if (draw) - Draw_Menu_Item(row, ICON_Version, F("Advanced"), nullptr, true); - else - Draw_Menu(Advanced); - break; - #if ENABLED(EEPROM_SETTINGS) - case CONTROL_SAVE: - if (draw) - Draw_Menu_Item(row, ICON_WriteEEPROM, F("Store Settings")); - else - AudioFeedback(settings.save()); - break; - case CONTROL_RESTORE: - if (draw) - Draw_Menu_Item(row, ICON_ReadEEPROM, F("Restore Settings")); - else - AudioFeedback(settings.load()); - break; - case CONTROL_RESET: - if (draw) - Draw_Menu_Item(row, ICON_Temperature, F("Reset to Defaults")); - else { - settings.reset(); - AudioFeedback(); - } - break; - #endif - case CONTROL_INFO: - if (draw) - Draw_Menu_Item(row, ICON_Info, F("Info")); - else - Draw_Menu(Info); - break; - } - break; - - case TempMenu: - - #define TEMP_BACK 0 - #define TEMP_HOTEND (TEMP_BACK + ENABLED(HAS_HOTEND)) - #define TEMP_BED (TEMP_HOTEND + ENABLED(HAS_HEATED_BED)) - #define TEMP_FAN (TEMP_BED + ENABLED(HAS_FAN)) - #define TEMP_PID (TEMP_FAN + ANY(HAS_HOTEND, HAS_HEATED_BED)) - #define TEMP_PREHEAT1 (TEMP_PID + (PREHEAT_COUNT >= 1)) - #define TEMP_PREHEAT2 (TEMP_PREHEAT1 + (PREHEAT_COUNT >= 2)) - #define TEMP_PREHEAT3 (TEMP_PREHEAT2 + (PREHEAT_COUNT >= 3)) - #define TEMP_PREHEAT4 (TEMP_PREHEAT3 + (PREHEAT_COUNT >= 4)) - #define TEMP_PREHEAT5 (TEMP_PREHEAT4 + (PREHEAT_COUNT >= 5)) - #define TEMP_TOTAL TEMP_PREHEAT5 - - switch (item) { - case TEMP_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Control, CONTROL_TEMP); - break; - #if HAS_HOTEND - case TEMP_HOTEND: - if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); - Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); - } - else - Modify_Value(thermalManager.temp_hotend[0].target, MIN_E_TEMP, MAX_E_TEMP, 1); - break; - #endif - #if HAS_HEATED_BED - case TEMP_BED: - if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); - Draw_Float(thermalManager.temp_bed.target, row, false, 1); - } - else - Modify_Value(thermalManager.temp_bed.target, MIN_BED_TEMP, MAX_BED_TEMP, 1); - break; - #endif - #if HAS_FAN - case TEMP_FAN: - if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); - Draw_Float(thermalManager.fan_speed[0], row, false, 1); - } - else - Modify_Value(thermalManager.fan_speed[0], MIN_FAN_SPEED, MAX_FAN_SPEED, 1); - break; - #endif - #if HAS_HOTEND || HAS_HEATED_BED - case TEMP_PID: - if (draw) - Draw_Menu_Item(row, ICON_Step, F("PID"), nullptr, true); - else - Draw_Menu(PID); - break; - #endif - - #define _TEMP_PREHEAT_CASE(N) \ - case TEMP_PREHEAT##N: { \ - if (draw) Draw_Menu_Item(row, ICON_Step, F(PREHEAT_## N ##_LABEL), nullptr, true); \ - else Draw_Menu(Preheat##N); \ - } break; - - REPEAT_1(PREHEAT_COUNT, _TEMP_PREHEAT_CASE) - } - break; - - #if HAS_HOTEND || HAS_HEATED_BED - case PID: - - #define PID_BACK 0 - #define PID_HOTEND (PID_BACK + ENABLED(HAS_HOTEND)) - #define PID_BED (PID_HOTEND + ENABLED(HAS_HEATED_BED)) - #define PID_CYCLES (PID_BED + 1) - #define PID_TOTAL PID_CYCLES - - static uint8_t PID_cycles = 5; - - switch (item) { - case PID_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(TempMenu, TEMP_PID); - break; - #if HAS_HOTEND - case PID_HOTEND: - if (draw) - Draw_Menu_Item(row, ICON_HotendTemp, F("Hotend"), nullptr, true); - else - Draw_Menu(HotendPID); - break; - #endif - #if HAS_HEATED_BED - case PID_BED: - if (draw) - Draw_Menu_Item(row, ICON_BedTemp, F("Bed"), nullptr, true); - else - Draw_Menu(BedPID); - break; - #endif - case PID_CYCLES: - if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, F("Cycles")); - Draw_Float(PID_cycles, row, false, 1); - } - else - Modify_Value(PID_cycles, 3, 50, 1); - break; - } - break; - #endif // HAS_HOTEND || HAS_HEATED_BED - - #if HAS_HOTEND - case HotendPID: - - #define HOTENDPID_BACK 0 - #define HOTENDPID_TUNE (HOTENDPID_BACK + 1) - #define HOTENDPID_TEMP (HOTENDPID_TUNE + 1) - #define HOTENDPID_KP (HOTENDPID_TEMP + 1) - #define HOTENDPID_KI (HOTENDPID_KP + 1) - #define HOTENDPID_KD (HOTENDPID_KI + 1) - #define HOTENDPID_TOTAL HOTENDPID_KD - - static uint16_t PID_e_temp = 180; - - switch (item) { - case HOTENDPID_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(PID, PID_HOTEND); - break; - case HOTENDPID_TUNE: - if (draw) - Draw_Menu_Item(row, ICON_HotendTemp, F("Autotune")); - else { - Popup_Handler(PIDWait); - sprintf_P(cmd, PSTR("M303 E0 C%i S%i U1"), PID_cycles, PID_e_temp); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Redraw_Menu(); - } - break; - case HOTENDPID_TEMP: - if (draw) { - Draw_Menu_Item(row, ICON_Temperature, F("Temperature")); - Draw_Float(PID_e_temp, row, false, 1); - } - else - Modify_Value(PID_e_temp, MIN_E_TEMP, MAX_E_TEMP, 1); - break; - case HOTENDPID_KP: - if (draw) { - Draw_Menu_Item(row, ICON_Version, F("Kp Value")); - Draw_Float(thermalManager.temp_hotend[0].pid.Kp, row, false, 100); - } - else - Modify_Value(thermalManager.temp_hotend[0].pid.Kp, 0, 5000, 100, thermalManager.updatePID); - break; - case HOTENDPID_KI: - if (draw) { - Draw_Menu_Item(row, ICON_Version, F("Ki Value")); - Draw_Float(unscalePID_i(thermalManager.temp_hotend[0].pid.Ki), row, false, 100); - } - else - Modify_Value(thermalManager.temp_hotend[0].pid.Ki, 0, 5000, 100, thermalManager.updatePID); - break; - case HOTENDPID_KD: - if (draw) { - Draw_Menu_Item(row, ICON_Version, F("Kd Value")); - Draw_Float(unscalePID_d(thermalManager.temp_hotend[0].pid.Kd), row, false, 100); - } - else - Modify_Value(thermalManager.temp_hotend[0].pid.Kd, 0, 5000, 100, thermalManager.updatePID); - break; - } - break; - #endif // HAS_HOTEND - - #if HAS_HEATED_BED - case BedPID: - - #define BEDPID_BACK 0 - #define BEDPID_TUNE (BEDPID_BACK + 1) - #define BEDPID_TEMP (BEDPID_TUNE + 1) - #define BEDPID_KP (BEDPID_TEMP + 1) - #define BEDPID_KI (BEDPID_KP + 1) - #define BEDPID_KD (BEDPID_KI + 1) - #define BEDPID_TOTAL BEDPID_KD - - static uint16_t PID_bed_temp = 60; - - switch (item) { - case BEDPID_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(PID, PID_BED); - break; - case BEDPID_TUNE: - if (draw) - Draw_Menu_Item(row, ICON_HotendTemp, F("Autotune")); - else { - Popup_Handler(PIDWait); - sprintf_P(cmd, PSTR("M303 E-1 C%i S%i U1"), PID_cycles, PID_bed_temp); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - Redraw_Menu(); - } - break; - case BEDPID_TEMP: - if (draw) { - Draw_Menu_Item(row, ICON_Temperature, F("Temperature")); - Draw_Float(PID_bed_temp, row, false, 1); - } - else - Modify_Value(PID_bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); - break; - case BEDPID_KP: - if (draw) { - Draw_Menu_Item(row, ICON_Version, F("Kp Value")); - Draw_Float(thermalManager.temp_bed.pid.Kp, row, false, 100); - } - else { - Modify_Value(thermalManager.temp_bed.pid.Kp, 0, 5000, 100, thermalManager.updatePID); - } - break; - case BEDPID_KI: - if (draw) { - Draw_Menu_Item(row, ICON_Version, F("Ki Value")); - Draw_Float(unscalePID_i(thermalManager.temp_bed.pid.Ki), row, false, 100); - } - else - Modify_Value(thermalManager.temp_bed.pid.Ki, 0, 5000, 100, thermalManager.updatePID); - break; - case BEDPID_KD: - if (draw) { - Draw_Menu_Item(row, ICON_Version, F("Kd Value")); - Draw_Float(unscalePID_d(thermalManager.temp_bed.pid.Kd), row, false, 100); - } - else - Modify_Value(thermalManager.temp_bed.pid.Kd, 0, 5000, 100, thermalManager.updatePID); - break; - } - break; - #endif // HAS_HEATED_BED - - #if HAS_PREHEAT - #define _PREHEAT_SUBMENU_CASE(N) case Preheat##N: preheat_submenu((N) - 1, item, TEMP_PREHEAT##N); break; - REPEAT_1(PREHEAT_COUNT, _PREHEAT_SUBMENU_CASE) - #endif - - case Motion: - - #define MOTION_BACK 0 - #define MOTION_HOMEOFFSETS (MOTION_BACK + 1) - #define MOTION_SPEED (MOTION_HOMEOFFSETS + 1) - #define MOTION_ACCEL (MOTION_SPEED + 1) - #define MOTION_JERK (MOTION_ACCEL + ENABLED(HAS_CLASSIC_JERK)) - #define MOTION_STEPS (MOTION_JERK + 1) - #define MOTION_FLOW (MOTION_STEPS + ENABLED(HAS_HOTEND)) - #define MOTION_TOTAL MOTION_FLOW - - switch (item) { - case MOTION_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Control, CONTROL_MOTION); - break; - case MOTION_HOMEOFFSETS: - if (draw) - Draw_Menu_Item(row, ICON_SetHome, F("Home Offsets"), nullptr, true); - else - Draw_Menu(HomeOffsets); - break; - case MOTION_SPEED: - if (draw) - Draw_Menu_Item(row, ICON_MaxSpeed, F("Max Speed"), nullptr, true); - else - Draw_Menu(MaxSpeed); - break; - case MOTION_ACCEL: - if (draw) - Draw_Menu_Item(row, ICON_MaxAccelerated, F("Max Acceleration"), nullptr, true); - else - Draw_Menu(MaxAcceleration); - break; - #if HAS_CLASSIC_JERK - case MOTION_JERK: - if (draw) - Draw_Menu_Item(row, ICON_MaxJerk, F("Max Jerk"), nullptr, true); - else - Draw_Menu(MaxJerk); - break; - #endif - case MOTION_STEPS: - if (draw) - Draw_Menu_Item(row, ICON_Step, F("Steps/mm"), nullptr, true); - else - Draw_Menu(Steps); - break; - #if HAS_HOTEND - case MOTION_FLOW: - if (draw) { - Draw_Menu_Item(row, ICON_Speed, F("Flow Rate")); - Draw_Float(planner.flow_percentage[0], row, false, 1); - } - else - Modify_Value(planner.flow_percentage[0], MIN_FLOW_RATE, MAX_FLOW_RATE, 1); - break; - #endif - } - break; - - case HomeOffsets: - - #define HOMEOFFSETS_BACK 0 - #define HOMEOFFSETS_XOFFSET (HOMEOFFSETS_BACK + 1) - #define HOMEOFFSETS_YOFFSET (HOMEOFFSETS_XOFFSET + 1) - #define HOMEOFFSETS_TOTAL HOMEOFFSETS_YOFFSET - - switch (item) { - case HOMEOFFSETS_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Motion, MOTION_HOMEOFFSETS); - break; - case HOMEOFFSETS_XOFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_StepX, F("X Offset")); - Draw_Float(home_offset.x, row, false, 100); - } - else - Modify_Value(home_offset.x, -MAX_XY_OFFSET, MAX_XY_OFFSET, 100); - break; - case HOMEOFFSETS_YOFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_StepY, F("Y Offset")); - Draw_Float(home_offset.y, row, false, 100); - } - else - Modify_Value(home_offset.y, -MAX_XY_OFFSET, MAX_XY_OFFSET, 100); - break; - } - break; - case MaxSpeed: - - #define SPEED_BACK 0 - #define SPEED_X (SPEED_BACK + 1) - #define SPEED_Y (SPEED_X + 1) - #define SPEED_Z (SPEED_Y + 1) - #define SPEED_E (SPEED_Z + ENABLED(HAS_HOTEND)) - #define SPEED_TOTAL SPEED_E - - switch (item) { - case SPEED_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Motion, MOTION_SPEED); - break; - case SPEED_X: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedX, F("X Axis")); - Draw_Float(planner.settings.max_feedrate_mm_s[X_AXIS], row, false, 1); - } - else - Modify_Value(planner.settings.max_feedrate_mm_s[X_AXIS], 0, default_max_feedrate[X_AXIS] * 2, 1); - break; - - #if HAS_Y_AXIS - case SPEED_Y: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedY, F("Y Axis")); - Draw_Float(planner.settings.max_feedrate_mm_s[Y_AXIS], row, false, 1); - } - else - Modify_Value(planner.settings.max_feedrate_mm_s[Y_AXIS], 0, default_max_feedrate[Y_AXIS] * 2, 1); - break; - #endif - - #if HAS_Z_AXIS - case SPEED_Z: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedZ, F("Z Axis")); - Draw_Float(planner.settings.max_feedrate_mm_s[Z_AXIS], row, false, 1); - } - else - Modify_Value(planner.settings.max_feedrate_mm_s[Z_AXIS], 0, default_max_feedrate[Z_AXIS] * 2, 1); - break; - #endif - - #if HAS_HOTEND - case SPEED_E: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedE, F("Extruder")); - Draw_Float(planner.settings.max_feedrate_mm_s[E_AXIS], row, false, 1); - } - else - Modify_Value(planner.settings.max_feedrate_mm_s[E_AXIS], 0, default_max_feedrate[E_AXIS] * 2, 1); - break; - #endif - } - break; - - case MaxAcceleration: - - #define ACCEL_BACK 0 - #define ACCEL_X (ACCEL_BACK + 1) - #define ACCEL_Y (ACCEL_X + 1) - #define ACCEL_Z (ACCEL_Y + 1) - #define ACCEL_E (ACCEL_Z + ENABLED(HAS_HOTEND)) - #define ACCEL_TOTAL ACCEL_E - - switch (item) { - case ACCEL_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Motion, MOTION_ACCEL); - break; - case ACCEL_X: - if (draw) { - Draw_Menu_Item(row, ICON_MaxAccX, F("X Axis")); - Draw_Float(planner.settings.max_acceleration_mm_per_s2[X_AXIS], row, false, 1); - } - else - Modify_Value(planner.settings.max_acceleration_mm_per_s2[X_AXIS], 0, default_max_acceleration[X_AXIS] * 2, 1); - break; - case ACCEL_Y: - if (draw) { - Draw_Menu_Item(row, ICON_MaxAccY, F("Y Axis")); - Draw_Float(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], row, false, 1); - } - else - Modify_Value(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], 0, default_max_acceleration[Y_AXIS] * 2, 1); - break; - case ACCEL_Z: - if (draw) { - Draw_Menu_Item(row, ICON_MaxAccZ, F("Z Axis")); - Draw_Float(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], row, false, 1); - } - else - Modify_Value(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], 0, default_max_acceleration[Z_AXIS] * 2, 1); - break; - #if HAS_HOTEND - case ACCEL_E: - if (draw) { - Draw_Menu_Item(row, ICON_MaxAccE, F("Extruder")); - Draw_Float(planner.settings.max_acceleration_mm_per_s2[E_AXIS], row, false, 1); - } - else - Modify_Value(planner.settings.max_acceleration_mm_per_s2[E_AXIS], 0, default_max_acceleration[E_AXIS] * 2, 1); - break; - #endif - } - break; - #if HAS_CLASSIC_JERK - case MaxJerk: - - #define JERK_BACK 0 - #define JERK_X (JERK_BACK + 1) - #define JERK_Y (JERK_X + 1) - #define JERK_Z (JERK_Y + 1) - #define JERK_E (JERK_Z + ENABLED(HAS_HOTEND)) - #define JERK_TOTAL JERK_E - - switch (item) { - case JERK_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Motion, MOTION_JERK); - break; - case JERK_X: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedJerkX, F("X Axis")); - Draw_Float(planner.max_jerk[X_AXIS], row, false, 10); - } - else - Modify_Value(planner.max_jerk[X_AXIS], 0, default_max_jerk[X_AXIS] * 2, 10); - break; - case JERK_Y: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedJerkY, F("Y Axis")); - Draw_Float(planner.max_jerk[Y_AXIS], row, false, 10); - } - else - Modify_Value(planner.max_jerk[Y_AXIS], 0, default_max_jerk[Y_AXIS] * 2, 10); - break; - case JERK_Z: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedJerkZ, F("Z Axis")); - Draw_Float(planner.max_jerk[Z_AXIS], row, false, 10); - } - else - Modify_Value(planner.max_jerk[Z_AXIS], 0, default_max_jerk[Z_AXIS] * 2, 10); - break; - #if HAS_HOTEND - case JERK_E: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedJerkE, F("Extruder")); - Draw_Float(planner.max_jerk[E_AXIS], row, false, 10); - } - else - Modify_Value(planner.max_jerk[E_AXIS], 0, default_max_jerk[E_AXIS] * 2, 10); - break; - #endif - } - break; - #endif - case Steps: - - #define STEPS_BACK 0 - #define STEPS_X (STEPS_BACK + 1) - #define STEPS_Y (STEPS_X + 1) - #define STEPS_Z (STEPS_Y + 1) - #define STEPS_E (STEPS_Z + ENABLED(HAS_HOTEND)) - #define STEPS_TOTAL STEPS_E - - switch (item) { - case STEPS_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Motion, MOTION_STEPS); - break; - case STEPS_X: - if (draw) { - Draw_Menu_Item(row, ICON_StepX, F("X Axis")); - Draw_Float(planner.settings.axis_steps_per_mm[X_AXIS], row, false, 10); - } - else - Modify_Value(planner.settings.axis_steps_per_mm[X_AXIS], 0, default_steps[X_AXIS] * 2, 10); - break; - case STEPS_Y: - if (draw) { - Draw_Menu_Item(row, ICON_StepY, F("Y Axis")); - Draw_Float(planner.settings.axis_steps_per_mm[Y_AXIS], row, false, 10); - } - else - Modify_Value(planner.settings.axis_steps_per_mm[Y_AXIS], 0, default_steps[Y_AXIS] * 2, 10); - break; - case STEPS_Z: - if (draw) { - Draw_Menu_Item(row, ICON_StepZ, F("Z Axis")); - Draw_Float(planner.settings.axis_steps_per_mm[Z_AXIS], row, false, 10); - } - else - Modify_Value(planner.settings.axis_steps_per_mm[Z_AXIS], 0, default_steps[Z_AXIS] * 2, 10); - break; - #if HAS_HOTEND - case STEPS_E: - if (draw) { - Draw_Menu_Item(row, ICON_StepE, F("Extruder")); - Draw_Float(planner.settings.axis_steps_per_mm[E_AXIS], row, false, 10); - } - else - Modify_Value(planner.settings.axis_steps_per_mm[E_AXIS], 0, 1000, 10); - break; - #endif - } - break; - - case Visual: - - #define VISUAL_BACK 0 - #define VISUAL_BACKLIGHT (VISUAL_BACK + 1) - #define VISUAL_BRIGHTNESS (VISUAL_BACKLIGHT + 1) - #define VISUAL_TIME_FORMAT (VISUAL_BRIGHTNESS + 1) - #define VISUAL_COLOR_THEMES (VISUAL_TIME_FORMAT + 1) - #define VISUAL_TOTAL VISUAL_COLOR_THEMES - - switch (item) { - case VISUAL_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Control, CONTROL_VISUAL); - break; - case VISUAL_BACKLIGHT: - if (draw) - Draw_Menu_Item(row, ICON_Brightness, F("Display Off")); - else - ui.set_brightness(0); - break; - case VISUAL_BRIGHTNESS: - if (draw) { - Draw_Menu_Item(row, ICON_Brightness, F("LCD Brightness")); - Draw_Float(ui.brightness, row, false, 1); - } - else - Modify_Value(ui.brightness, LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, 1, ui.refresh_brightness); - break; - case VISUAL_TIME_FORMAT: - if (draw) { - Draw_Menu_Item(row, ICON_PrintTime, F("Progress as __h__m")); - Draw_Checkbox(row, eeprom_settings.time_format_textual); - } - else { - eeprom_settings.time_format_textual = !eeprom_settings.time_format_textual; - Draw_Checkbox(row, eeprom_settings.time_format_textual); - } - break; - case VISUAL_COLOR_THEMES: - if (draw) - Draw_Menu_Item(row, ICON_MaxSpeed, F("UI Color Settings"), nullptr, true); - else - Draw_Menu(ColorSettings); - break; - } - break; - - case ColorSettings: - - #define COLORSETTINGS_BACK 0 - #define COLORSETTINGS_CURSOR (COLORSETTINGS_BACK + 1) - #define COLORSETTINGS_SPLIT_LINE (COLORSETTINGS_CURSOR + 1) - #define COLORSETTINGS_MENU_TOP_TXT (COLORSETTINGS_SPLIT_LINE + 1) - #define COLORSETTINGS_MENU_TOP_BG (COLORSETTINGS_MENU_TOP_TXT + 1) - #define COLORSETTINGS_HIGHLIGHT_BORDER (COLORSETTINGS_MENU_TOP_BG + 1) - #define COLORSETTINGS_PROGRESS_PERCENT (COLORSETTINGS_HIGHLIGHT_BORDER + 1) - #define COLORSETTINGS_PROGRESS_TIME (COLORSETTINGS_PROGRESS_PERCENT + 1) - #define COLORSETTINGS_PROGRESS_STATUS_BAR (COLORSETTINGS_PROGRESS_TIME + 1) - #define COLORSETTINGS_PROGRESS_STATUS_AREA (COLORSETTINGS_PROGRESS_STATUS_BAR + 1) - #define COLORSETTINGS_PROGRESS_COORDINATES (COLORSETTINGS_PROGRESS_STATUS_AREA + 1) - #define COLORSETTINGS_PROGRESS_COORDINATES_LINE (COLORSETTINGS_PROGRESS_COORDINATES + 1) - #define COLORSETTINGS_TOTAL COLORSETTINGS_PROGRESS_COORDINATES_LINE - - switch (item) { - case COLORSETTINGS_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Visual, VISUAL_COLOR_THEMES); - break; - case COLORSETTINGS_CURSOR: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Cursor")); - Draw_Option(eeprom_settings.cursor_color, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.cursor_color, color_names, Custom_Colors); - break; - case COLORSETTINGS_SPLIT_LINE: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Split Line")); - Draw_Option(eeprom_settings.menu_split_line, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.menu_split_line, color_names, Custom_Colors); - break; - case COLORSETTINGS_MENU_TOP_TXT: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Header Text")); - Draw_Option(eeprom_settings.menu_top_txt, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.menu_top_txt, color_names, Custom_Colors); - break; - case COLORSETTINGS_MENU_TOP_BG: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Header Bg")); - Draw_Option(eeprom_settings.menu_top_bg, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.menu_top_bg, color_names, Custom_Colors); - break; - case COLORSETTINGS_HIGHLIGHT_BORDER: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Highlight Box")); - Draw_Option(eeprom_settings.highlight_box, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.highlight_box, color_names, Custom_Colors); - break; - case COLORSETTINGS_PROGRESS_PERCENT: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Progress Percent")); - Draw_Option(eeprom_settings.progress_percent, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.progress_percent, color_names, Custom_Colors); - break; - case COLORSETTINGS_PROGRESS_TIME: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Progress Time")); - Draw_Option(eeprom_settings.progress_time, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.progress_time, color_names, Custom_Colors); - break; - case COLORSETTINGS_PROGRESS_STATUS_BAR: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Status Bar Text")); - Draw_Option(eeprom_settings.status_bar_text, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.status_bar_text, color_names, Custom_Colors); - break; - case COLORSETTINGS_PROGRESS_STATUS_AREA: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Status Area Text")); - Draw_Option(eeprom_settings.status_area_text, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.status_area_text, color_names, Custom_Colors); - break; - case COLORSETTINGS_PROGRESS_COORDINATES: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Coordinates Text")); - Draw_Option(eeprom_settings.coordinates_text, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.coordinates_text, color_names, Custom_Colors); - break; - case COLORSETTINGS_PROGRESS_COORDINATES_LINE: - if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, F("Coordinates Line")); - Draw_Option(eeprom_settings.coordinates_split_line, color_names, row, false, true); - } - else - Modify_Option(eeprom_settings.coordinates_split_line, color_names, Custom_Colors); - break; - } // switch (item) - break; - - case Advanced: - - #define ADVANCED_BACK 0 - #define ADVANCED_BEEPER (ADVANCED_BACK + ENABLED(SOUND_MENU_ITEM)) - #define ADVANCED_PROBE (ADVANCED_BEEPER + ENABLED(HAS_BED_PROBE)) - #define ADVANCED_CORNER (ADVANCED_PROBE + 1) - #define ADVANCED_LA (ADVANCED_CORNER + ENABLED(LIN_ADVANCE)) - #define ADVANCED_LOAD (ADVANCED_LA + ENABLED(ADVANCED_PAUSE_FEATURE)) - #define ADVANCED_UNLOAD (ADVANCED_LOAD + ENABLED(ADVANCED_PAUSE_FEATURE)) - #define ADVANCED_COLD_EXTRUDE (ADVANCED_UNLOAD + ENABLED(PREVENT_COLD_EXTRUSION)) - #define ADVANCED_FILSENSORENABLED (ADVANCED_COLD_EXTRUDE + ENABLED(FILAMENT_RUNOUT_SENSOR)) - #define ADVANCED_FILSENSORDISTANCE (ADVANCED_FILSENSORENABLED + ENABLED(HAS_FILAMENT_RUNOUT_DISTANCE)) - #define ADVANCED_POWER_LOSS (ADVANCED_FILSENSORDISTANCE + ENABLED(POWER_LOSS_RECOVERY)) - #define ADVANCED_TOTAL ADVANCED_POWER_LOSS - - switch (item) { - case ADVANCED_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Control, CONTROL_ADVANCED); - break; - - #if ENABLED(SOUND_MENU_ITEM) - case ADVANCED_BEEPER: - if (draw) { - Draw_Menu_Item(row, ICON_Version, F("LCD Beeper")); - Draw_Checkbox(row, ui.buzzer_enabled); - } - else { - ui.buzzer_enabled = !ui.buzzer_enabled; - Draw_Checkbox(row, ui.buzzer_enabled); - } - break; - #endif - - #if HAS_BED_PROBE - case ADVANCED_PROBE: - if (draw) - Draw_Menu_Item(row, ICON_StepX, F("Probe"), nullptr, true); - else - Draw_Menu(ProbeMenu); - break; - #endif - - case ADVANCED_CORNER: - if (draw) { - Draw_Menu_Item(row, ICON_MaxAccelerated, F("Bed Screw Inset")); - Draw_Float(corner_pos, row, false, 10); - } - else - Modify_Value(corner_pos, 1, 100, 10); - break; - - #if ENABLED(LIN_ADVANCE) - case ADVANCED_LA: - if (draw) { - Draw_Menu_Item(row, ICON_MaxAccelerated, F("Lin Advance Kp")); - Draw_Float(planner.extruder_advance_K[0], row, false, 100); - } - else - Modify_Value(planner.extruder_advance_K[0], 0, 10, 100); - break; - #endif - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - case ADVANCED_LOAD: - if (draw) { - Draw_Menu_Item(row, ICON_WriteEEPROM, F("Load Length")); - Draw_Float(fc_settings[0].load_length, row, false, 1); - } - else - Modify_Value(fc_settings[0].load_length, 0, EXTRUDE_MAXLENGTH, 1); - break; - case ADVANCED_UNLOAD: - if (draw) { - Draw_Menu_Item(row, ICON_ReadEEPROM, F("Unload Length")); - Draw_Float(fc_settings[0].unload_length, row, false, 1); - } - else - Modify_Value(fc_settings[0].unload_length, 0, EXTRUDE_MAXLENGTH, 1); - break; - #endif // ADVANCED_PAUSE_FEATURE - - #if ENABLED(PREVENT_COLD_EXTRUSION) - case ADVANCED_COLD_EXTRUDE: - if (draw) { - Draw_Menu_Item(row, ICON_Cool, F("Min Extrusion T")); - Draw_Float(thermalManager.extrude_min_temp, row, false, 1); - } - else { - Modify_Value(thermalManager.extrude_min_temp, 0, MAX_E_TEMP, 1); - thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0); - } - break; - #endif - - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - case ADVANCED_FILSENSORENABLED: - if (draw) { - Draw_Menu_Item(row, ICON_Extruder, F("Filament Sensor")); - Draw_Checkbox(row, runout.enabled); - } - else { - runout.enabled = !runout.enabled; - Draw_Checkbox(row, runout.enabled); - } - break; - - #if ENABLED(HAS_FILAMENT_RUNOUT_DISTANCE) - case ADVANCED_FILSENSORDISTANCE: - if (draw) { - Draw_Menu_Item(row, ICON_MaxAccE, F("Runout Distance")); - Draw_Float(runout.runout_distance(), row, false, 10); - } - else - Modify_Value(runout.runout_distance(), 0, 999, 10); - break; - #endif - #endif // FILAMENT_RUNOUT_SENSOR - - #if ENABLED(POWER_LOSS_RECOVERY) - case ADVANCED_POWER_LOSS: - if (draw) { - Draw_Menu_Item(row, ICON_Motion, F("Power-loss recovery")); - Draw_Checkbox(row, recovery.enabled); - } - else { - recovery.enable(!recovery.enabled); - Draw_Checkbox(row, recovery.enabled); - } - break; - #endif - } - break; - - #if HAS_BED_PROBE - case ProbeMenu: - - #define PROBE_BACK 0 - #define PROBE_XOFFSET (PROBE_BACK + 1) - #define PROBE_YOFFSET (PROBE_XOFFSET + 1) - #define PROBE_TEST (PROBE_YOFFSET + 1) - #define PROBE_TEST_COUNT (PROBE_TEST + 1) - #define PROBE_TOTAL PROBE_TEST_COUNT - - static uint8_t testcount = 4; - - switch (item) { - case PROBE_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Advanced, ADVANCED_PROBE); - break; - - case PROBE_XOFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_StepX, F("Probe X Offset")); - Draw_Float(probe.offset.x, row, false, 10); - } - else - Modify_Value(probe.offset.x, -MAX_XY_OFFSET, MAX_XY_OFFSET, 10); - break; - case PROBE_YOFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_StepY, F("Probe Y Offset")); - Draw_Float(probe.offset.y, row, false, 10); - } - else - Modify_Value(probe.offset.y, -MAX_XY_OFFSET, MAX_XY_OFFSET, 10); - break; - case PROBE_TEST: - if (draw) - Draw_Menu_Item(row, ICON_StepY, F("M48 Probe Test")); - else { - sprintf_P(cmd, PSTR("G28O\nM48 X%s Y%s P%i"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), testcount); - gcode.process_subcommands_now(cmd); - } - break; - case PROBE_TEST_COUNT: - if (draw) { - Draw_Menu_Item(row, ICON_StepY, F("Probe Test Count")); - Draw_Float(testcount, row, false, 1); - } - else - Modify_Value(testcount, 4, 50, 1); - break; - } - break; - #endif - - case InfoMain: - case Info: - - #define INFO_BACK 0 - #define INFO_PRINTCOUNT (INFO_BACK + ENABLED(PRINTCOUNTER)) - #define INFO_PRINTTIME (INFO_PRINTCOUNT + ENABLED(PRINTCOUNTER)) - #define INFO_SIZE (INFO_PRINTTIME + 1) - #define INFO_VERSION (INFO_SIZE + 1) - #define INFO_CONTACT (INFO_VERSION + 1) - #define INFO_TOTAL INFO_BACK - - switch (item) { - case INFO_BACK: - if (draw) { - Draw_Menu_Item(row, ICON_Back, F("Back")); - - #if ENABLED(PRINTCOUNTER) - char row1[50], row2[50], buf[32]; - printStatistics ps = print_job_timer.getStats(); - - sprintf_P(row1, PSTR("%i prints, %i finished"), ps.totalPrints, ps.finishedPrints); - sprintf_P(row2, PSTR("%s m filament used"), dtostrf(ps.filamentUsed / 1000, 1, 2, str_1)); - Draw_Menu_Item(INFO_PRINTCOUNT, ICON_HotendTemp, row1, row2, false, true); - - duration_t(print_job_timer.getStats().printTime).toString(buf); - sprintf_P(row1, PSTR("Printed: %s"), buf); - duration_t(print_job_timer.getStats().longestPrint).toString(buf); - sprintf_P(row2, PSTR("Longest: %s"), buf); - Draw_Menu_Item(INFO_PRINTTIME, ICON_PrintTime, row1, row2, false, true); - #endif - - Draw_Menu_Item(INFO_SIZE, ICON_PrintSize, F(MACHINE_SIZE), nullptr, false, true); - Draw_Menu_Item(INFO_VERSION, ICON_Version, F(SHORT_BUILD_VERSION), nullptr, false, true); - Draw_Menu_Item(INFO_CONTACT, ICON_Contact, F(CORP_WEBSITE), nullptr, false, true); - } - else { - if (menu == Info) - Draw_Menu(Control, CONTROL_INFO); - else - Draw_Main_Menu(3); - } - break; - } - break; - - #if HAS_MESH - case Leveling: - - #define LEVELING_BACK 0 - #define LEVELING_ACTIVE (LEVELING_BACK + 1) - #define LEVELING_GET_TILT (LEVELING_ACTIVE + BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL)) - #define LEVELING_GET_MESH (LEVELING_GET_TILT + 1) - #define LEVELING_MANUAL (LEVELING_GET_MESH + 1) - #define LEVELING_VIEW (LEVELING_MANUAL + 1) - #define LEVELING_SETTINGS (LEVELING_VIEW + 1) - #define LEVELING_SLOT (LEVELING_SETTINGS + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_LOAD (LEVELING_SLOT + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_SAVE (LEVELING_LOAD + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_TOTAL LEVELING_SAVE - - switch (item) { - case LEVELING_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Main_Menu(3); - break; - case LEVELING_ACTIVE: - if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguration, F("Leveling Active")); - Draw_Checkbox(row, planner.leveling_active); - } - else { - if (!planner.leveling_active) { - set_bed_leveling_enabled(!planner.leveling_active); - if (!planner.leveling_active) { - Confirm_Handler(LevelError); - break; - } - } - else - set_bed_leveling_enabled(!planner.leveling_active); - Draw_Checkbox(row, planner.leveling_active); - } - break; - #if BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL) - case LEVELING_GET_TILT: - if (draw) - Draw_Menu_Item(row, ICON_Tilt, F("Autotilt Current Mesh")); - else { - if (ubl.storage_slot < 0) { - Popup_Handler(MeshSlot); - break; - } - Popup_Handler(Home); - gcode.home_all_axes(true); - Popup_Handler(Level); - if (mesh_conf.tilt_grid > 1) { - sprintf_P(cmd, PSTR("G29 J%i"), mesh_conf.tilt_grid); - gcode.process_subcommands_now(cmd); - } - else - gcode.process_subcommands_now(F("G29 J")); - planner.synchronize(); - Redraw_Menu(); - } - break; - #endif - case LEVELING_GET_MESH: - if (draw) - Draw_Menu_Item(row, ICON_Mesh, F("Create New Mesh")); - else { - Popup_Handler(Home); - gcode.home_all_axes(true); - #if ENABLED(AUTO_BED_LEVELING_UBL) - #if ENABLED(PREHEAT_BEFORE_LEVELING) - Popup_Handler(Heating); - probe.preheat_for_probing(LEVELING_NOZZLE_TEMP, LEVELING_BED_TEMP); - #endif - #if HAS_BED_PROBE - Popup_Handler(Level); - gcode.process_subcommands_now(F("G29 P0\nG29 P1")); - gcode.process_subcommands_now(F("G29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nM420 S1")); - planner.synchronize(); - Update_Status("Probed all reachable points"); - Popup_Handler(SaveLevel); - #else - level_state = planner.leveling_active; - set_bed_leveling_enabled(false); - mesh_conf.goto_mesh_value = true; - mesh_conf.mesh_x = mesh_conf.mesh_y = 0; - Popup_Handler(MoveWait); - mesh_conf.manual_move(); - Draw_Menu(UBLMesh); - #endif - #elif HAS_BED_PROBE - Popup_Handler(Level); - gcode.process_subcommands_now(F("G29")); - planner.synchronize(); - Popup_Handler(SaveLevel); - #else - level_state = planner.leveling_active; - set_bed_leveling_enabled(false); - gridpoint = 1; - Popup_Handler(MoveWait); - gcode.process_subcommands_now(F("G29")); - planner.synchronize(); - Draw_Menu(ManualMesh); - #endif - } - break; - case LEVELING_MANUAL: - if (draw) - Draw_Menu_Item(row, ICON_Mesh, F("Manual Tuning"), nullptr, true); - else { - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (!leveling_is_valid()) { - Confirm_Handler(InvalidMesh); - break; - } - #endif - #if ENABLED(AUTO_BED_LEVELING_UBL) - if (ubl.storage_slot < 0) { - Popup_Handler(MeshSlot); - break; - } - #endif - if (axes_should_home()) { - Popup_Handler(Home); - gcode.home_all_axes(true); - } - level_state = planner.leveling_active; - set_bed_leveling_enabled(false); - mesh_conf.goto_mesh_value = false; - #if ENABLED(PREHEAT_BEFORE_LEVELING) - Popup_Handler(Heating); - #if HAS_HOTEND - if (thermalManager.degTargetHotend(0) < LEVELING_NOZZLE_TEMP) - thermalManager.setTargetHotend(LEVELING_NOZZLE_TEMP, 0); - #endif - #if HAS_HEATED_BED - if (thermalManager.degTargetBed() < LEVELING_BED_TEMP) - thermalManager.setTargetBed(LEVELING_BED_TEMP); - #endif - TERN_(HAS_HOTEND, thermalManager.wait_for_hotend(0)); - TERN_(HAS_HEATED_BED, thermalManager.wait_for_bed_heating()); - #endif - Popup_Handler(MoveWait); - mesh_conf.manual_move(); - Draw_Menu(LevelManual); - } - break; - case LEVELING_VIEW: - if (draw) - Draw_Menu_Item(row, ICON_Mesh, GET_TEXT(MSG_MESH_VIEW), nullptr, true); - else { - #if ENABLED(AUTO_BED_LEVELING_UBL) - if (ubl.storage_slot < 0) { - Popup_Handler(MeshSlot); - break; - } - #endif - Draw_Menu(LevelView); - } - break; - case LEVELING_SETTINGS: - if (draw) - Draw_Menu_Item(row, ICON_Step, F("Leveling Settings"), nullptr, true); - else - Draw_Menu(LevelSettings); - break; - #if ENABLED(AUTO_BED_LEVELING_UBL) - case LEVELING_SLOT: - if (draw) { - Draw_Menu_Item(row, ICON_PrintSize, F("Mesh Slot")); - Draw_Float(ubl.storage_slot, row, false, 1); - } - else - Modify_Value(ubl.storage_slot, 0, settings.calc_num_meshes() - 1, 1); - break; - case LEVELING_LOAD: - if (draw) - Draw_Menu_Item(row, ICON_ReadEEPROM, F("Load Mesh")); - else { - if (ubl.storage_slot < 0) { - Popup_Handler(MeshSlot); - break; - } - gcode.process_subcommands_now(F("G29 L")); - planner.synchronize(); - AudioFeedback(true); - } - break; - case LEVELING_SAVE: - if (draw) - Draw_Menu_Item(row, ICON_WriteEEPROM, F("Save Mesh")); - else { - if (ubl.storage_slot < 0) { - Popup_Handler(MeshSlot); - break; - } - gcode.process_subcommands_now(F("G29 S")); - planner.synchronize(); - AudioFeedback(true); - } - break; - #endif - } - break; - - case LevelView: - - #define LEVELING_VIEW_BACK 0 - #define LEVELING_VIEW_MESH (LEVELING_VIEW_BACK + 1) - #define LEVELING_VIEW_TEXT (LEVELING_VIEW_MESH + 1) - #define LEVELING_VIEW_ASYMMETRIC (LEVELING_VIEW_TEXT + 1) - #define LEVELING_VIEW_TOTAL LEVELING_VIEW_ASYMMETRIC - - switch (item) { - case LEVELING_VIEW_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Leveling, LEVELING_VIEW); - break; - case LEVELING_VIEW_MESH: - if (draw) - Draw_Menu_Item(row, ICON_PrintSize, GET_TEXT(MSG_MESH_VIEW), nullptr, true); - else - Draw_Menu(MeshViewer); - break; - case LEVELING_VIEW_TEXT: - if (draw) { - Draw_Menu_Item(row, ICON_Contact, F("Viewer Show Values")); - Draw_Checkbox(row, mesh_conf.viewer_print_value); - } - else { - mesh_conf.viewer_print_value = !mesh_conf.viewer_print_value; - Draw_Checkbox(row, mesh_conf.viewer_print_value); - } - break; - case LEVELING_VIEW_ASYMMETRIC: - if (draw) { - Draw_Menu_Item(row, ICON_Axis, F("Viewer Asymmetric")); - Draw_Checkbox(row, mesh_conf.viewer_asymmetric_range); - } - else { - mesh_conf.viewer_asymmetric_range = !mesh_conf.viewer_asymmetric_range; - Draw_Checkbox(row, mesh_conf.viewer_asymmetric_range); - } - break; - } - break; - - case LevelSettings: - - #define LEVELING_SETTINGS_BACK 0 - #define LEVELING_SETTINGS_FADE (LEVELING_SETTINGS_BACK + 1) - #define LEVELING_SETTINGS_TILT (LEVELING_SETTINGS_FADE + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_SETTINGS_PLANE (LEVELING_SETTINGS_TILT + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_SETTINGS_ZERO (LEVELING_SETTINGS_PLANE + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_SETTINGS_UNDEF (LEVELING_SETTINGS_ZERO + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_SETTINGS_TOTAL LEVELING_SETTINGS_UNDEF - - switch (item) { - case LEVELING_SETTINGS_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Menu(Leveling, LEVELING_SETTINGS); - break; - case LEVELING_SETTINGS_FADE: - if (draw) { - Draw_Menu_Item(row, ICON_Fade, F("Fade Mesh within")); - Draw_Float(planner.z_fade_height, row, false, 1); - } - else { - Modify_Value(planner.z_fade_height, 0, Z_MAX_POS, 1); - planner.z_fade_height = -1; - set_z_fade_height(planner.z_fade_height); - } - break; - - #if ENABLED(AUTO_BED_LEVELING_UBL) - case LEVELING_SETTINGS_TILT: - if (draw) { - Draw_Menu_Item(row, ICON_Tilt, F("Tilting Grid Size")); - Draw_Float(mesh_conf.tilt_grid, row, false, 1); - } - else - Modify_Value(mesh_conf.tilt_grid, 1, 8, 1); - break; - case LEVELING_SETTINGS_PLANE: - if (draw) - Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Convert Mesh to Plane")); - else { - if (mesh_conf.create_plane_from_mesh()) break; - gcode.process_subcommands_now(F("M420 S1")); - planner.synchronize(); - AudioFeedback(true); - } - break; - case LEVELING_SETTINGS_ZERO: - if (draw) - Draw_Menu_Item(row, ICON_Mesh, F("Zero Current Mesh")); - else - ZERO(Z_VALUES_ARR); - break; - case LEVELING_SETTINGS_UNDEF: - if (draw) - Draw_Menu_Item(row, ICON_Mesh, F("Clear Current Mesh")); - else - ubl.invalidate(); - break; - #endif // AUTO_BED_LEVELING_UBL - } - break; - - case MeshViewer: - #define MESHVIEW_BACK 0 - #define MESHVIEW_TOTAL MESHVIEW_BACK - - if (item == MESHVIEW_BACK) { - if (draw) { - Draw_Menu_Item(0, ICON_Back, F("Back")); - mesh_conf.Draw_Bed_Mesh(); - mesh_conf.Set_Mesh_Viewer_Status(); - } - else if (!mesh_conf.drawing_mesh) { - Draw_Menu(LevelView, LEVELING_VIEW_MESH); - Update_Status(""); - } - } - break; - - case LevelManual: - - #define LEVELING_M_BACK 0 - #define LEVELING_M_X (LEVELING_M_BACK + 1) - #define LEVELING_M_Y (LEVELING_M_X + 1) - #define LEVELING_M_NEXT (LEVELING_M_Y + 1) - #define LEVELING_M_OFFSET (LEVELING_M_NEXT + 1) - #define LEVELING_M_UP (LEVELING_M_OFFSET + 1) - #define LEVELING_M_DOWN (LEVELING_M_UP + 1) - #define LEVELING_M_GOTO_VALUE (LEVELING_M_DOWN + 1) - #define LEVELING_M_UNDEF (LEVELING_M_GOTO_VALUE + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_M_TOTAL LEVELING_M_UNDEF - - switch (item) { - case LEVELING_M_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else { - set_bed_leveling_enabled(level_state); - TERN_(AUTO_BED_LEVELING_BILINEAR, bbl.refresh_bed_level()); - Draw_Menu(Leveling, LEVELING_MANUAL); - } - break; - case LEVELING_M_X: - if (draw) { - Draw_Menu_Item(row, ICON_MoveX, F("Mesh Point X")); - Draw_Float(mesh_conf.mesh_x, row, 0, 1); - } - else - Modify_Value(mesh_conf.mesh_x, 0, GRID_MAX_POINTS_X - 1, 1); - break; - case LEVELING_M_Y: - if (draw) { - Draw_Menu_Item(row, ICON_MoveY, F("Mesh Point Y")); - Draw_Float(mesh_conf.mesh_y, row, 0, 1); - } - else - Modify_Value(mesh_conf.mesh_y, 0, GRID_MAX_POINTS_Y - 1, 1); - break; - case LEVELING_M_NEXT: - if (draw) - Draw_Menu_Item(row, ICON_More, F("Next Point")); - else { - if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) { - if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 0) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 1)) - mesh_conf.mesh_y++; - else if (mesh_conf.mesh_y % 2 == 0) - mesh_conf.mesh_x++; - else - mesh_conf.mesh_x--; - mesh_conf.manual_move(); - } - } - break; - case LEVELING_M_OFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, F("Point Z Offset")); - Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); - } - else { - if (isnan(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y])) - Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; - Modify_Value(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); - } - break; - case LEVELING_M_UP: - if (draw) - Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); - else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { - Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; - gcode.process_subcommands_now(F("M290 Z0.01")); - planner.synchronize(); - current_position.z += 0.01f; - sync_plan_position(); - Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); - } - break; - case LEVELING_M_DOWN: - if (draw) - Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); - else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { - Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; - gcode.process_subcommands_now(F("M290 Z-0.01")); - planner.synchronize(); - current_position.z -= 0.01f; - sync_plan_position(); - Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); - } - break; - case LEVELING_M_GOTO_VALUE: - if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguration, F("Go to Mesh Z Value")); - Draw_Checkbox(row, mesh_conf.goto_mesh_value); - } - else { - mesh_conf.goto_mesh_value = !mesh_conf.goto_mesh_value; - current_position.z = 0; - mesh_conf.manual_move(true); - Draw_Checkbox(row, mesh_conf.goto_mesh_value); - } - break; - #if ENABLED(AUTO_BED_LEVELING_UBL) - case LEVELING_M_UNDEF: - if (draw) - Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Clear Point Value")); - else { - mesh_conf.manual_value_update(true); - Redraw_Menu(false); - } - break; - #endif - } - break; - #endif // HAS_MESH - - #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE - case UBLMesh: - - #define UBL_M_BACK 0 - #define UBL_M_NEXT (UBL_M_BACK + 1) - #define UBL_M_PREV (UBL_M_NEXT + 1) - #define UBL_M_OFFSET (UBL_M_PREV + 1) - #define UBL_M_UP (UBL_M_OFFSET + 1) - #define UBL_M_DOWN (UBL_M_UP + 1) - #define UBL_M_TOTAL UBL_M_DOWN - - switch (item) { - case UBL_M_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else { - set_bed_leveling_enabled(level_state); - Draw_Menu(Leveling, LEVELING_GET_MESH); - } - break; - case UBL_M_NEXT: - if (draw) { - if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) - Draw_Menu_Item(row, ICON_More, F("Next Point")); - else - Draw_Menu_Item(row, ICON_More, F("Save Mesh")); - } - else { - if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) { - if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 0) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 1)) - mesh_conf.mesh_y++; - else if (mesh_conf.mesh_y % 2 == 0) - mesh_conf.mesh_x++; - else - mesh_conf.mesh_x--; - mesh_conf.manual_move(); - } - else { - gcode.process_subcommands_now(F("G29 S")); - planner.synchronize(); - AudioFeedback(true); - Draw_Menu(Leveling, LEVELING_GET_MESH); - } - } - break; - case UBL_M_PREV: - if (draw) - Draw_Menu_Item(row, ICON_More, F("Previous Point")); - else { - if (mesh_conf.mesh_x != 0 || mesh_conf.mesh_y != 0) { - if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 1) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 0)) - mesh_conf.mesh_y--; - else if (mesh_conf.mesh_y % 2 == 0) - mesh_conf.mesh_x--; - else - mesh_conf.mesh_x++; - mesh_conf.manual_move(); - } - } - break; - case UBL_M_OFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, F("Point Z Offset")); - Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); - } - else { - if (isnan(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y])) - Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; - Modify_Value(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); - } - break; - case UBL_M_UP: - if (draw) - Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); - else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { - Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; - gcode.process_subcommands_now(F("M290 Z0.01")); - planner.synchronize(); - current_position.z += 0.01f; - sync_plan_position(); - Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); - } - break; - case UBL_M_DOWN: - if (draw) - Draw_Menu_Item(row, ICON_Axis, F("Microstep Down")); - else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { - Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; - gcode.process_subcommands_now(F("M290 Z-0.01")); - planner.synchronize(); - current_position.z -= 0.01f; - sync_plan_position(); - Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); - } - break; - } - break; - #endif // AUTO_BED_LEVELING_UBL && !HAS_BED_PROBE - - #if ENABLED(PROBE_MANUALLY) - case ManualMesh: - - #define MMESH_BACK 0 - #define MMESH_NEXT (MMESH_BACK + 1) - #define MMESH_OFFSET (MMESH_NEXT + 1) - #define MMESH_UP (MMESH_OFFSET + 1) - #define MMESH_DOWN (MMESH_UP + 1) - #define MMESH_OLD (MMESH_DOWN + 1) - #define MMESH_TOTAL MMESH_OLD - - switch (item) { - case MMESH_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Cancel")); - else { - gcode.process_subcommands_now(F("G29 A")); - planner.synchronize(); - set_bed_leveling_enabled(level_state); - Draw_Menu(Leveling, LEVELING_GET_MESH); - } - break; - case MMESH_NEXT: - if (draw) { - if (gridpoint < GRID_MAX_POINTS) - Draw_Menu_Item(row, ICON_More, F("Next Point")); - else - Draw_Menu_Item(row, ICON_More, F("Save Mesh")); - } - else if (gridpoint < GRID_MAX_POINTS) { - Popup_Handler(MoveWait); - gcode.process_subcommands_now(F("G29")); - planner.synchronize(); - gridpoint++; - Redraw_Menu(); - } - else { - gcode.process_subcommands_now(F("G29")); - planner.synchronize(); - AudioFeedback(settings.save()); - Draw_Menu(Leveling, LEVELING_GET_MESH); - } - break; - case MMESH_OFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, F("Z Position")); - current_position.z = MANUAL_PROBE_START_Z; - Draw_Float(current_position.z, row, false, 100); - } - else - Modify_Value(current_position.z, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); - break; - case MMESH_UP: - if (draw) - Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); - else if (current_position.z < MAX_Z_OFFSET) { - gcode.process_subcommands_now(F("M290 Z0.01")); - planner.synchronize(); - current_position.z += 0.01f; - sync_plan_position(); - Draw_Float(current_position.z, row - 1, false, 100); - } - break; - case MMESH_DOWN: - if (draw) - Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); - else if (current_position.z > MIN_Z_OFFSET) { - gcode.process_subcommands_now(F("M290 Z-0.01")); - planner.synchronize(); - current_position.z -= 0.01f; - sync_plan_position(); - Draw_Float(current_position.z, row - 2, false, 100); - } - break; - case MMESH_OLD: - uint8_t mesh_x, mesh_y; - // 0,0 -> 1,0 -> 2,0 -> 2,1 -> 1,1 -> 0,1 -> 0,2 -> 1,2 -> 2,2 - mesh_y = (gridpoint - 1) / GRID_MAX_POINTS_Y; - mesh_x = (gridpoint - 1) % GRID_MAX_POINTS_X; - - if (mesh_y % 2 == 1) - mesh_x = GRID_MAX_POINTS_X - mesh_x - 1; - - const float currval = Z_VALUES_ARR[mesh_x][mesh_y]; - - if (draw) { - Draw_Menu_Item(row, ICON_Zoffset, F("Goto Mesh Value")); - Draw_Float(currval, row, false, 100); - } - else if (!isnan(currval)) { - current_position.z = currval; - planner.synchronize(); - planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); - planner.synchronize(); - Draw_Float(current_position.z, row - 3, false, 100); - } - break; - } - break; - #endif // PROBE_MANUALLY - - case Tune: - - #define TUNE_BACK 0 - #define TUNE_SPEED (TUNE_BACK + 1) - #define TUNE_FLOW (TUNE_SPEED + ENABLED(HAS_HOTEND)) - #define TUNE_HOTEND (TUNE_FLOW + ENABLED(HAS_HOTEND)) - #define TUNE_BED (TUNE_HOTEND + ENABLED(HAS_HEATED_BED)) - #define TUNE_FAN (TUNE_BED + ENABLED(HAS_FAN)) - #define TUNE_ZOFFSET (TUNE_FAN + ENABLED(HAS_ZOFFSET_ITEM)) - #define TUNE_ZUP (TUNE_ZOFFSET + ENABLED(HAS_ZOFFSET_ITEM)) - #define TUNE_ZDOWN (TUNE_ZUP + ENABLED(HAS_ZOFFSET_ITEM)) - #define TUNE_CHANGEFIL (TUNE_ZDOWN + ENABLED(FILAMENT_LOAD_UNLOAD_GCODES)) - #define TUNE_FILSENSORENABLED (TUNE_CHANGEFIL + ENABLED(FILAMENT_RUNOUT_SENSOR)) - #define TUNE_BACKLIGHT_OFF (TUNE_FILSENSORENABLED + 1) - #define TUNE_BACKLIGHT (TUNE_BACKLIGHT_OFF + 1) - #define TUNE_TOTAL TUNE_BACKLIGHT - - switch (item) { - case TUNE_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Back")); - else - Draw_Print_Screen(); - break; - case TUNE_SPEED: - if (draw) { - Draw_Menu_Item(row, ICON_Speed, F("Print Speed")); - Draw_Float(feedrate_percentage, row, false, 1); - } - else - Modify_Value(feedrate_percentage, MIN_PRINT_SPEED, MAX_PRINT_SPEED, 1); - break; - - #if HAS_HOTEND - case TUNE_FLOW: - if (draw) { - Draw_Menu_Item(row, ICON_Speed, F("Flow Rate")); - Draw_Float(planner.flow_percentage[0], row, false, 1); - } - else - Modify_Value(planner.flow_percentage[0], MIN_FLOW_RATE, MAX_FLOW_RATE, 1); - break; - case TUNE_HOTEND: - if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); - Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); - } - else - Modify_Value(thermalManager.temp_hotend[0].target, MIN_E_TEMP, MAX_E_TEMP, 1); - break; - #endif - - #if HAS_HEATED_BED - case TUNE_BED: - if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); - Draw_Float(thermalManager.temp_bed.target, row, false, 1); - } - else - Modify_Value(thermalManager.temp_bed.target, MIN_BED_TEMP, MAX_BED_TEMP, 1); - break; - #endif - - #if HAS_FAN - case TUNE_FAN: - if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); - Draw_Float(thermalManager.fan_speed[0], row, false, 1); - } - else - Modify_Value(thermalManager.fan_speed[0], MIN_FAN_SPEED, MAX_FAN_SPEED, 1); - break; - #endif - - #if HAS_ZOFFSET_ITEM - case TUNE_ZOFFSET: - if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, F("Z-Offset")); - Draw_Float(zoffsetvalue, row, false, 100); - } - else - Modify_Value(zoffsetvalue, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); - break; - case TUNE_ZUP: - if (draw) - Draw_Menu_Item(row, ICON_Axis, F("Z-Offset Up")); - else if (zoffsetvalue < MAX_Z_OFFSET) { - gcode.process_subcommands_now(F("M290 Z0.01")); - zoffsetvalue += 0.01; - Draw_Float(zoffsetvalue, row - 1, false, 100); - } - break; - case TUNE_ZDOWN: - if (draw) - Draw_Menu_Item(row, ICON_AxisD, F("Z-Offset Down")); - else if (zoffsetvalue > MIN_Z_OFFSET) { - gcode.process_subcommands_now(F("M290 Z-0.01")); - zoffsetvalue -= 0.01; - Draw_Float(zoffsetvalue, row - 2, false, 100); - } - break; - #endif - - #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - case TUNE_CHANGEFIL: - if (draw) - Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament")); - else - Popup_Handler(ConfFilChange); - break; - #endif - - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - case TUNE_FILSENSORENABLED: - if (draw) { - Draw_Menu_Item(row, ICON_Extruder, F("Filament Sensor")); - Draw_Checkbox(row, runout.enabled); - } - else { - runout.enabled = !runout.enabled; - Draw_Checkbox(row, runout.enabled); - } - break; - #endif - - case TUNE_BACKLIGHT_OFF: - if (draw) - Draw_Menu_Item(row, ICON_Brightness, F("Display Off")); - else - ui.set_brightness(0); - break; - case TUNE_BACKLIGHT: - if (draw) { - Draw_Menu_Item(row, ICON_Brightness, F("LCD Brightness")); - Draw_Float(ui.brightness, row, false, 1); - } - else - Modify_Value(ui.brightness, LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, 1, ui.refresh_brightness); - break; - } - break; - - #if HAS_PREHEAT && HAS_HOTEND - - case PreheatHotend: - - #define PREHEATHOTEND_BACK 0 - #define PREHEATHOTEND_CONTINUE (PREHEATHOTEND_BACK + 1) - #define PREHEATHOTEND_1 (PREHEATHOTEND_CONTINUE + (PREHEAT_COUNT >= 1)) - #define PREHEATHOTEND_2 (PREHEATHOTEND_1 + (PREHEAT_COUNT >= 2)) - #define PREHEATHOTEND_3 (PREHEATHOTEND_2 + (PREHEAT_COUNT >= 3)) - #define PREHEATHOTEND_4 (PREHEATHOTEND_3 + (PREHEAT_COUNT >= 4)) - #define PREHEATHOTEND_5 (PREHEATHOTEND_4 + (PREHEAT_COUNT >= 5)) - #define PREHEATHOTEND_CUSTOM (PREHEATHOTEND_5 + 1) - #define PREHEATHOTEND_TOTAL PREHEATHOTEND_CUSTOM - - switch (item) { - case PREHEATHOTEND_BACK: - if (draw) - Draw_Menu_Item(row, ICON_Back, F("Cancel")); - else { - thermalManager.setTargetHotend(0, 0); - thermalManager.set_fan_speed(0, 0); - Redraw_Menu(false, true, true); - } - break; - case PREHEATHOTEND_CONTINUE: - if (draw) - Draw_Menu_Item(row, ICON_SetEndTemp, F("Continue")); - else { - Popup_Handler(Heating); - thermalManager.wait_for_hotend(0); - switch (last_menu) { - case Prepare: - Popup_Handler(FilChange); - sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now(cmd); - break; - #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - case ChangeFilament: - switch (last_selection) { - case CHANGEFIL_LOAD: - Popup_Handler(FilLoad); - gcode.process_subcommands_now(F("M701")); - planner.synchronize(); - Redraw_Menu(true, true, true); - break; - case CHANGEFIL_UNLOAD: - Popup_Handler(FilLoad, true); - gcode.process_subcommands_now(F("M702")); - planner.synchronize(); - Redraw_Menu(true, true, true); - break; - case CHANGEFIL_CHANGE: - Popup_Handler(FilChange); - sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now(cmd); - break; - } - break; - #endif - default: - Redraw_Menu(true, true, true); - break; - } - } - break; - - - #define _PREHEAT_HOTEND_CASE(N) \ - case PREHEATHOTEND_##N: \ - if (draw) Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_## N ##_LABEL)); \ - else ui.preheat_hotend_and_fan((N) - 1); \ - break; - - REPEAT_1(PREHEAT_COUNT, _PREHEAT_HOTEND_CASE) - - case PREHEATHOTEND_CUSTOM: - if (draw) { - Draw_Menu_Item(row, ICON_Temperature, F("Custom")); - Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); - } - else - Modify_Value(thermalManager.temp_hotend[0].target, EXTRUDE_MINTEMP, MAX_E_TEMP, 1); - break; - } - break; - - #endif // HAS_PREHEAT && HAS_HOTEND - } -} - -FSTR_P CrealityDWINClass::Get_Menu_Title(uint8_t menu) { - switch (menu) { - case MainMenu: return F("Main Menu"); - case Prepare: return F("Prepare"); - case HomeMenu: return F("Homing Menu"); - case Move: return F("Move"); - case ManualLevel: return F("Manual Leveling"); - #if HAS_ZOFFSET_ITEM - case ZOffset: return F("Z Offset"); - #endif - #if HAS_PREHEAT - case Preheat: return F("Preheat"); - #endif - #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - case ChangeFilament: return F("Change Filament"); - #endif - case Control: return F("Control"); - case TempMenu: return F("Temperature"); - #if HAS_HOTEND || HAS_HEATED_BED - case PID: return F("PID Menu"); - #endif - #if HAS_HOTEND - case HotendPID: return F("Hotend PID Settings"); - #endif - #if HAS_HEATED_BED - case BedPID: return F("Bed PID Settings"); - #endif - #if HAS_PREHEAT - #define _PREHEAT_TITLE_CASE(N) case Preheat##N: return F(PREHEAT_## N ##_LABEL " Settings"); - REPEAT_1(PREHEAT_COUNT, _PREHEAT_TITLE_CASE) - #endif - case Motion: return F("Motion Settings"); - case HomeOffsets: return F("Home Offsets"); - case MaxSpeed: return F("Max Speed"); - case MaxAcceleration: return F("Max Acceleration"); - #if HAS_CLASSIC_JERK - case MaxJerk: return F("Max Jerk"); - #endif - case Steps: return F("Steps/mm"); - case Visual: return F("Visual Settings"); - case Advanced: return F("Advanced Settings"); - #if HAS_BED_PROBE - case ProbeMenu: return F("Probe Menu"); - #endif - case ColorSettings: return F("UI Color Settings"); - case Info: return F("Info"); - case InfoMain: return F("Info"); - #if HAS_MESH - case Leveling: return F("Leveling"); - case LevelView: return GET_TEXT_F(MSG_MESH_VIEW); - case LevelSettings: return F("Leveling Settings"); - case MeshViewer: return GET_TEXT_F(MSG_MESH_VIEW); - case LevelManual: return F("Manual Tuning"); - #endif - #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE - case UBLMesh: return F("UBL Bed Leveling"); - #endif - #if ENABLED(PROBE_MANUALLY) - case ManualMesh: return F("Mesh Bed Leveling"); - #endif - case Tune: return F("Tune"); - case PreheatHotend: return F("Preheat Hotend"); - } - return F(""); -} - -uint8_t CrealityDWINClass::Get_Menu_Size(uint8_t menu) { - switch (menu) { - case Prepare: return PREPARE_TOTAL; - case HomeMenu: return HOME_TOTAL; - case Move: return MOVE_TOTAL; - case ManualLevel: return MLEVEL_TOTAL; - #if HAS_ZOFFSET_ITEM - case ZOffset: return ZOFFSET_TOTAL; - #endif - #if HAS_PREHEAT - case Preheat: return PREHEAT_TOTAL; - #endif - #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - case ChangeFilament: return CHANGEFIL_TOTAL; - #endif - case Control: return CONTROL_TOTAL; - case TempMenu: return TEMP_TOTAL; - #if HAS_HOTEND || HAS_HEATED_BED - case PID: return PID_TOTAL; - #endif - #if HAS_HOTEND - case HotendPID: return HOTENDPID_TOTAL; - #endif - #if HAS_HEATED_BED - case BedPID: return BEDPID_TOTAL; - #endif - #if HAS_PREHEAT - case Preheat1 ... CAT(Preheat, PREHEAT_COUNT): - return PREHEAT_SUBMENU_TOTAL; - #endif - case Motion: return MOTION_TOTAL; - case HomeOffsets: return HOMEOFFSETS_TOTAL; - case MaxSpeed: return SPEED_TOTAL; - case MaxAcceleration: return ACCEL_TOTAL; - #if HAS_CLASSIC_JERK - case MaxJerk: return JERK_TOTAL; - #endif - case Steps: return STEPS_TOTAL; - case Visual: return VISUAL_TOTAL; - case Advanced: return ADVANCED_TOTAL; - #if HAS_BED_PROBE - case ProbeMenu: return PROBE_TOTAL; - #endif - case Info: return INFO_TOTAL; - case InfoMain: return INFO_TOTAL; - #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE - case UBLMesh: return UBL_M_TOTAL; - #endif - #if ENABLED(PROBE_MANUALLY) - case ManualMesh: return MMESH_TOTAL; - #endif - #if HAS_MESH - case Leveling: return LEVELING_TOTAL; - case LevelView: return LEVELING_VIEW_TOTAL; - case LevelSettings: return LEVELING_SETTINGS_TOTAL; - case MeshViewer: return MESHVIEW_TOTAL; - case LevelManual: return LEVELING_M_TOTAL; - #endif - case Tune: return TUNE_TOTAL; - - #if HAS_PREHEAT && HAS_HOTEND - case PreheatHotend: return PREHEATHOTEND_TOTAL; - #endif - - case ColorSettings: return COLORSETTINGS_TOTAL; - } - return 0; -} - -/* Popup Config */ - -void CrealityDWINClass::Popup_Handler(PopupID popupid, bool option/*=false*/) { - popup = last_popup = popupid; - switch (popupid) { - case Pause: Draw_Popup(F("Pause Print"), F(""), F(""), Popup); break; - case Stop: Draw_Popup(F("Stop Print"), F(""), F(""), Popup); break; - case Resume: Draw_Popup(F("Resume Print?"), F("Looks Like the last"), F("print was interrupted."), Popup); break; - case ConfFilChange: Draw_Popup(F("Confirm Filament Change"), F(""), F(""), Popup); break; - case PurgeMore: Draw_Popup(F("Purge more filament?"), F("(Cancel to finish process)"), F(""), Popup); break; - case SaveLevel: Draw_Popup(F("Leveling Complete"), F("Save to EEPROM?"), F(""), Popup); break; - case MeshSlot: Draw_Popup(F("Mesh slot not selected"), F("(Confirm to select slot 0)"), F(""), Popup); break; - case ETemp: Draw_Popup(F("Nozzle is too cold"), F("Open Preheat Menu?"), F(""), Popup); break; - case ManualProbing: Draw_Popup(F("Manual Probing"), F("(Confirm to probe)"), F("(cancel to exit)"), Popup); break; - case Level: Draw_Popup(F("Auto Bed Leveling"), F("Please wait until done."), F(""), Wait, ICON_AutoLeveling); break; - case Home: Draw_Popup(option ? F("Parking") : F("Homing"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; - case MoveWait: Draw_Popup(F("Moving to Point"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; - case Heating: Draw_Popup(F("Heating"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; - case FilLoad: Draw_Popup(option ? F("Unloading Filament") : F("Loading Filament"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; - case FilChange: Draw_Popup(F("Filament Change"), F("Please wait for prompt."), F(""), Wait, ICON_BLTouch); break; - case TempWarn: Draw_Popup(option ? F("Nozzle temp too low!") : F("Nozzle temp too high!"), F(""), F(""), Wait, option ? ICON_TempTooLow : ICON_TempTooHigh); break; - case Runout: Draw_Popup(F("Filament Runout"), F(""), F(""), Wait, ICON_BLTouch); break; - case PIDWait: Draw_Popup(F("PID Autotune"), F("in process"), F("Please wait until done."), Wait, ICON_BLTouch); break; - case Resuming: Draw_Popup(F("Resuming Print"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; - default: break; - } -} - -void CrealityDWINClass::Confirm_Handler(PopupID popupid) { - popup = popupid; - switch (popupid) { - case FilInsert: Draw_Popup(F("Insert Filament"), F("Press to Continue"), F(""), Confirm); break; - case HeaterTime: Draw_Popup(F("Heater Timed Out"), F("Press to Reheat"), F(""), Confirm); break; - case UserInput: Draw_Popup(F("Waiting for Input"), F("Press to Continue"), F(""), Confirm); break; - case LevelError: Draw_Popup(F("Couldn't enable Leveling"), F("(Valid mesh must exist)"), F(""), Confirm); break; - case InvalidMesh: Draw_Popup(F("Valid mesh must exist"), F("before tuning can be"), F("performed"), Confirm); break; - default: break; - } -} - -/* Navigation and Control */ - -void CrealityDWINClass::Main_Menu_Control() { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW && selection < PAGE_COUNT - 1) { - selection++; // Select Down - Main_Menu_Icons(); - } - else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { - selection--; // Select Up - Main_Menu_Icons(); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) - switch (selection) { - case PAGE_PRINT: card.mount(); Draw_SD_List(); break; - case PAGE_PREPARE: Draw_Menu(Prepare); break; - case PAGE_CONTROL: Draw_Menu(Control); break; - case PAGE_INFO_LEVELING: Draw_Menu(TERN(HAS_MESH, Leveling, InfoMain)); break; - } - DWIN_UpdateLCD(); -} - -void CrealityDWINClass::Menu_Control() { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW && selection < Get_Menu_Size(active_menu)) { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); - selection++; // Select Down - if (selection > scrollpos+MROWS) { - scrollpos++; - DWIN_Frame_AreaMove(1, 2, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); - Menu_Item_Handler(active_menu, selection); - } - DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); - } - else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); - selection--; // Select Up - if (selection < scrollpos) { - scrollpos--; - DWIN_Frame_AreaMove(1, 3, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); - Menu_Item_Handler(active_menu, selection); - } - DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) - Menu_Item_Handler(active_menu, selection, false); - DWIN_UpdateLCD(); -} - -void CrealityDWINClass::Value_Control() { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW) - tempvalue += EncoderRate.encoderMoveValue; - else if (encoder_diffState == ENCODER_DIFF_CCW) - tempvalue -= EncoderRate.encoderMoveValue; - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - process = Menu; - EncoderRate.enabled = false; - Draw_Float(tempvalue / valueunit, selection - scrollpos, false, valueunit); - DWIN_UpdateLCD(); - if (active_menu == ZOffset && liveadjust) { - planner.synchronize(); - current_position.z += (tempvalue / valueunit - zoffsetvalue); - planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); - current_position.z = 0; - sync_plan_position(); - } - else if (active_menu == Tune && selection == TUNE_ZOFFSET) { - sprintf_P(cmd, PSTR("M290 Z%s"), dtostrf((tempvalue / valueunit - zoffsetvalue), 1, 3, str_1)); - gcode.process_subcommands_now(cmd); - } - if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) - tempvalue = scalePID_i(tempvalue); - if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Kd) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Kd)) - tempvalue = scalePID_d(tempvalue); - switch (valuetype) { - case 0: *(float*)valuepointer = tempvalue / valueunit; break; - case 1: *(uint8_t*)valuepointer = tempvalue / valueunit; break; - case 2: *(uint16_t*)valuepointer = tempvalue / valueunit; break; - case 3: *(int16_t*)valuepointer = tempvalue / valueunit; break; - case 4: *(uint32_t*)valuepointer = tempvalue / valueunit; break; - case 5: *(int8_t*)valuepointer = tempvalue / valueunit; break; - } - switch (active_menu) { - case Move: - planner.synchronize(); - planner.buffer_line(current_position, manual_feedrate_mm_s[selection - 1], active_extruder); - break; - #if HAS_MESH - case ManualMesh: - planner.synchronize(); - planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); - planner.synchronize(); - break; - case UBLMesh: mesh_conf.manual_move(true); break; - case LevelManual: mesh_conf.manual_move(selection == LEVELING_M_OFFSET); break; - #endif - } - if (valuepointer == &planner.flow_percentage[0]) - planner.refresh_e_factor(0); - if (funcpointer) funcpointer(); - return; - } - NOLESS(tempvalue, (valuemin * valueunit)); - NOMORE(tempvalue, (valuemax * valueunit)); - Draw_Float(tempvalue / valueunit, selection - scrollpos, true, valueunit); - DWIN_UpdateLCD(); - if (active_menu == Move && livemove) { - *(float*)valuepointer = tempvalue / valueunit; - planner.buffer_line(current_position, manual_feedrate_mm_s[selection - 1], active_extruder); - } -} - -void CrealityDWINClass::Option_Control() { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW) - tempvalue += EncoderRate.encoderMoveValue; - else if (encoder_diffState == ENCODER_DIFF_CCW) - tempvalue -= EncoderRate.encoderMoveValue; - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - process = Menu; - EncoderRate.enabled = false; - if (valuepointer == &color_names) { - switch (selection) { - case COLORSETTINGS_CURSOR: eeprom_settings.cursor_color = tempvalue; break; - case COLORSETTINGS_SPLIT_LINE: eeprom_settings.menu_split_line = tempvalue; break; - case COLORSETTINGS_MENU_TOP_BG: eeprom_settings.menu_top_bg = tempvalue; break; - case COLORSETTINGS_MENU_TOP_TXT: eeprom_settings.menu_top_txt = tempvalue; break; - case COLORSETTINGS_HIGHLIGHT_BORDER: eeprom_settings.highlight_box = tempvalue; break; - case COLORSETTINGS_PROGRESS_PERCENT: eeprom_settings.progress_percent = tempvalue; break; - case COLORSETTINGS_PROGRESS_TIME: eeprom_settings.progress_time = tempvalue; break; - case COLORSETTINGS_PROGRESS_STATUS_BAR: eeprom_settings.status_bar_text = tempvalue; break; - case COLORSETTINGS_PROGRESS_STATUS_AREA: eeprom_settings.status_area_text = tempvalue; break; - case COLORSETTINGS_PROGRESS_COORDINATES: eeprom_settings.coordinates_text = tempvalue; break; - case COLORSETTINGS_PROGRESS_COORDINATES_LINE: eeprom_settings.coordinates_split_line = tempvalue; break; - } - Redraw_Screen(); - } - else if (valuepointer == &preheat_modes) - preheatmode = tempvalue; - - Draw_Option(tempvalue, static_cast(valuepointer), selection - scrollpos, false, (valuepointer == &color_names)); - DWIN_UpdateLCD(); - return; - } - NOLESS(tempvalue, valuemin); - NOMORE(tempvalue, valuemax); - Draw_Option(tempvalue, static_cast(valuepointer), selection - scrollpos, true); - DWIN_UpdateLCD(); -} - -void CrealityDWINClass::File_Control() { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - static uint8_t filescrl = 0; - if (encoder_diffState == ENCODER_DIFF_NO) { - if (selection > 0) { - card.getfilename_sorted(SD_ORDER(selection - 1, card.get_num_Files())); - char * const filename = card.longest_filename(); - size_t len = strlen(filename); - int8_t pos = len; - if (!card.flag.filenameIsDir) - while (pos && filename[pos] != '.') pos--; - if (pos > MENU_CHAR_LIMIT) { - static millis_t time = 0; - if (PENDING(millis(), time)) return; - time = millis() + 200; - pos -= filescrl; - len = _MIN(pos, MENU_CHAR_LIMIT); - char name[len + 1]; - if (pos >= 0) { - LOOP_L_N(i, len) name[i] = filename[i + filescrl]; - } - else { - LOOP_L_N(i, MENU_CHAR_LIMIT + pos) name[i] = ' '; - LOOP_S_L_N(i, MENU_CHAR_LIMIT + pos, MENU_CHAR_LIMIT) name[i] = filename[i - (MENU_CHAR_LIMIT + pos)]; - } - name[len] = '\0'; - DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); - Draw_Menu_Item(selection - scrollpos, card.flag.filenameIsDir ? ICON_More : ICON_File, name); - if (-pos >= MENU_CHAR_LIMIT) filescrl = 0; - filescrl++; - DWIN_UpdateLCD(); - } - } - return; - } - if (encoder_diffState == ENCODER_DIFF_CW && selection < card.get_num_Files()) { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); - if (selection > 0) { - DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); - Draw_SD_Item(selection, selection - scrollpos); - } - filescrl = 0; - selection++; // Select Down - if (selection > scrollpos + MROWS) { - scrollpos++; - DWIN_Frame_AreaMove(1, 2, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); - Draw_SD_Item(selection, selection - scrollpos); - } - DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); - } - else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); - DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); - Draw_SD_Item(selection, selection - scrollpos); - filescrl = 0; - selection--; // Select Up - if (selection < scrollpos) { - scrollpos--; - DWIN_Frame_AreaMove(1, 3, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); - Draw_SD_Item(selection, selection - scrollpos); - } - DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (selection == 0) { - if (card.flag.workDirIsRoot) { - process = Main; - Draw_Main_Menu(); - } - else { - card.cdup(); - Draw_SD_List(); - } - } - else { - card.getfilename_sorted(SD_ORDER(selection - 1, card.get_num_Files())); - if (card.flag.filenameIsDir) { - card.cd(card.filename); - Draw_SD_List(); - } - else { - card.openAndPrintFile(card.filename); - } - } - } - DWIN_UpdateLCD(); -} - -void CrealityDWINClass::Print_Screen_Control() { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW && selection < PRINT_COUNT - 1) { - selection++; // Select Down - Print_Screen_Icons(); - } - else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { - selection--; // Select Up - Print_Screen_Icons(); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (selection) { - case PRINT_SETUP: - Draw_Menu(Tune); - Update_Status_Bar(true); - break; - case PRINT_PAUSE_RESUME: - if (paused) { - if (sdprint) { - wait_for_user = false; - #if ENABLED(PARK_HEAD_ON_PAUSE) - card.startOrResumeFilePrinting(); - TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); - #else - char cmnd[20]; - #if HAS_HEATED_BED - cmnd[sprintf_P(cmnd, PSTR("M140 S%i"), pausebed)] = '\0'; - gcode.process_subcommands_now(cmnd); - #endif - #if HAS_EXTRUDERS - cmnd[sprintf_P(cmnd, PSTR("M109 S%i"), pausetemp)] = '\0'; - gcode.process_subcommands_now(cmnd); - #endif - TERN_(HAS_FAN, thermalManager.fan_speed[0] = pausefan); - planner.synchronize(); - TERN_(SDSUPPORT, queue.inject(F("M24"))); - #endif - } - else { - TERN_(HOST_ACTION_COMMANDS, hostui.resume()); - } - Draw_Print_Screen(); - } - else - Popup_Handler(Pause); - break; - case PRINT_STOP: Popup_Handler(Stop); break; - } - } - DWIN_UpdateLCD(); -} - -void CrealityDWINClass::Popup_Control() { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW && selection < 1) { - selection++; - Popup_Select(); - } - else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { - selection--; - Popup_Select(); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (popup) { - case Pause: - if (selection == 0) { - if (sdprint) { - #if ENABLED(POWER_LOSS_RECOVERY) - if (recovery.enabled) recovery.save(true); - #endif - #if ENABLED(PARK_HEAD_ON_PAUSE) - Popup_Handler(Home, true); - #if ENABLED(SDSUPPORT) - if (IS_SD_PRINTING()) card.pauseSDPrint(); - #endif - planner.synchronize(); - queue.inject(F("M125")); - planner.synchronize(); - #else - queue.inject(F("M25")); - TERN_(HAS_HOTEND, pausetemp = thermalManager.temp_hotend[0].target); - TERN_(HAS_HEATED_BED, pausebed = thermalManager.temp_bed.target); - TERN_(HAS_FAN, pausefan = thermalManager.fan_speed[0]); - thermalManager.cooldown(); - #endif - } - else { - TERN_(HOST_ACTION_COMMANDS, hostui.pause()); - } - } - Draw_Print_Screen(); - break; - case Stop: - if (selection == 0) { - if (sdprint) { - ui.abort_print(); - thermalManager.cooldown(); - } - else { - TERN_(HOST_ACTION_COMMANDS, hostui.cancel()); - } - } - else - Draw_Print_Screen(); - break; - case Resume: - if (selection == 0) - queue.inject(F("M1000")); - else { - queue.inject(F("M1000 C")); - Draw_Main_Menu(); - } - break; - - #if HAS_HOTEND - case ETemp: - if (selection == 0) { - thermalManager.setTargetHotend(EXTRUDE_MINTEMP, 0); - thermalManager.set_fan_speed(0, MAX_FAN_SPEED); - Draw_Menu(PreheatHotend); - } - else - Redraw_Menu(true, true, false); - break; - #endif - - #if HAS_BED_PROBE - case ManualProbing: - if (selection == 0) { - char buf[80]; - const float dif = probe.probe_at_point(current_position.x, current_position.y, PROBE_PT_STOW, 0, false) - corner_avg; - sprintf_P(buf, dif > 0 ? PSTR("Corner is %smm high") : PSTR("Corner is %smm low"), dtostrf(abs(dif), 1, 3, str_1)); - Update_Status(buf); - } - else { - Redraw_Menu(true, true, false); - Update_Status(""); - } - break; - #endif - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - case ConfFilChange: - if (selection == 0) { - if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) - Popup_Handler(ETemp); - else { - if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { - Popup_Handler(Heating); - thermalManager.wait_for_hotend(0); - } - Popup_Handler(FilChange); - sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now(cmd); - } - } - else - Redraw_Menu(true, true, false); - break; - case PurgeMore: - if (selection == 0) { - pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; - Popup_Handler(FilChange); - } - else { - pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; - if (printing) Popup_Handler(Resuming); - else Redraw_Menu(true, true, (active_menu==PreheatHotend)); - } - break; - #endif // ADVANCED_PAUSE_FEATURE - - #if HAS_MESH - case SaveLevel: - if (selection == 0) { - #if ENABLED(AUTO_BED_LEVELING_UBL) - gcode.process_subcommands_now(F("G29 S")); - planner.synchronize(); - AudioFeedback(true); - #else - AudioFeedback(settings.save()); - #endif - } - Draw_Menu(Leveling, LEVELING_GET_MESH); - break; - #endif - - #if ENABLED(AUTO_BED_LEVELING_UBL) - case MeshSlot: - if (selection == 0) ubl.storage_slot = 0; - Redraw_Menu(true, true); - break; - #endif - default: break; - } - } - DWIN_UpdateLCD(); -} - -void CrealityDWINClass::Confirm_Control() { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (popup) { - case Complete: - Draw_Main_Menu(); - break; - case FilInsert: - Popup_Handler(FilChange); - wait_for_user = false; - break; - case HeaterTime: - Popup_Handler(Heating); - wait_for_user = false; - break; - default: - Redraw_Menu(true, true, false); - wait_for_user = false; - break; - } - } - DWIN_UpdateLCD(); -} - -/* In-Menu Value Modification */ - -void CrealityDWINClass::Setup_Value(float value, float min, float max, float unit, uint8_t type) { - if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) - tempvalue = unscalePID_i(value) * unit; - else if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Kd) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Kd)) - tempvalue = unscalePID_d(value) * unit; - else - tempvalue = value * unit; - valuemin = min; - valuemax = max; - valueunit = unit; - valuetype = type; - process = Value; - EncoderRate.enabled = true; - Draw_Float(tempvalue / unit, selection - scrollpos, true, valueunit); -} - -void CrealityDWINClass::Modify_Value(float &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { - valuepointer = &value; - funcpointer = f; - Setup_Value((float)value, min, max, unit, 0); -} -void CrealityDWINClass::Modify_Value(uint8_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { - valuepointer = &value; - funcpointer = f; - Setup_Value((float)value, min, max, unit, 1); -} -void CrealityDWINClass::Modify_Value(uint16_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { - valuepointer = &value; - funcpointer = f; - Setup_Value((float)value, min, max, unit, 2); -} -void CrealityDWINClass::Modify_Value(int16_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { - valuepointer = &value; - funcpointer = f; - Setup_Value((float)value, min, max, unit, 3); -} -void CrealityDWINClass::Modify_Value(uint32_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { - valuepointer = &value; - funcpointer = f; - Setup_Value((float)value, min, max, unit, 4); -} -void CrealityDWINClass::Modify_Value(int8_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { - valuepointer = &value; - funcpointer = f; - Setup_Value((float)value, min, max, unit, 5); -} - -void CrealityDWINClass::Modify_Option(uint8_t value, const char * const * options, uint8_t max) { - tempvalue = value; - valuepointer = const_cast(options); - valuemin = 0; - valuemax = max; - process = Option; - EncoderRate.enabled = true; - Draw_Option(value, options, selection - scrollpos, true); -} - -/* Main Functions */ - -void CrealityDWINClass::Update_Status(const char * const text) { - if (strncmp_P(text, PSTR(""), 3) == 0) { - LOOP_L_N(i, _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text))) filename[i] = text[i + 3]; - filename[_MIN((size_t)LONG_FILENAME_LENGTH - 1, strlen(text))] = '\0'; - Draw_Print_Filename(true); - } - else { - LOOP_L_N(i, _MIN((size_t)64, strlen(text))) statusmsg[i] = text[i]; - statusmsg[_MIN((size_t)64, strlen(text))] = '\0'; - } -} - -void CrealityDWINClass::Start_Print(bool sd) { - sdprint = sd; - if (!printing) { - printing = true; - statusmsg[0] = '\0'; - if (sd) { - #if ENABLED(POWER_LOSS_RECOVERY) - if (recovery.valid()) { - SdFile *diveDir = nullptr; - const char * const fname = card.diveToFile(true, diveDir, recovery.info.sd_filename); - card.selectFileByName(fname); - } - #endif - strcpy(filename, card.longest_filename()); - } - else - strcpy_P(filename, PSTR("Host Print")); - TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(0)); - TERN_(USE_M73_REMAINING_TIME, ui.set_remaining_time(0)); - Draw_Print_Screen(); - } -} - -void CrealityDWINClass::Stop_Print() { - printing = false; - sdprint = false; - thermalManager.cooldown(); - TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(100 * (PROGRESS_SCALE))); - TERN_(USE_M73_REMAINING_TIME, ui.set_remaining_time(0)); - Draw_Print_confirm(); -} - -void CrealityDWINClass::Update() { - State_Update(); - Screen_Update(); - switch (process) { - case Main: Main_Menu_Control(); break; - case Menu: Menu_Control(); break; - case Value: Value_Control(); break; - case Option: Option_Control(); break; - case File: File_Control(); break; - case Print: Print_Screen_Control(); break; - case Popup: Popup_Control(); break; - case Confirm: Confirm_Control(); break; - } -} - -void MarlinUI::update() { CrealityDWIN.Update(); } - -#if HAS_LCD_BRIGHTNESS - void MarlinUI::_set_brightness() { DWIN_LCD_Brightness(backlight ? brightness : 0); } -#endif - -void CrealityDWINClass::State_Update() { - if ((print_job_timer.isRunning() || print_job_timer.isPaused()) != printing) { - if (!printing) Start_Print(card.isFileOpen() || TERN0(POWER_LOSS_RECOVERY, recovery.valid())); - else Stop_Print(); - } - if (print_job_timer.isPaused() != paused) { - paused = print_job_timer.isPaused(); - if (process == Print) Print_Screen_Icons(); - if (process == Wait && !paused) Redraw_Menu(true, true); - } - if (wait_for_user && !(process == Confirm) && !print_job_timer.isPaused()) - Confirm_Handler(UserInput); - #if ENABLED(ADVANCED_PAUSE_FEATURE) - if (process == Popup && popup == PurgeMore) { - if (pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE) - Popup_Handler(FilChange); - else if (pause_menu_response == PAUSE_RESPONSE_RESUME_PRINT) { - if (printing) Popup_Handler(Resuming); - else Redraw_Menu(true, true, (active_menu==PreheatHotend)); - } - } - #endif - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - static bool ranout = false; - if (runout.filament_ran_out != ranout) { - ranout = runout.filament_ran_out; - if (ranout) Popup_Handler(Runout); - } - #endif -} - -void CrealityDWINClass::Screen_Update() { - const millis_t ms = millis(); - static millis_t scrltime = 0; - if (ELAPSED(ms, scrltime)) { - scrltime = ms + 200; - Update_Status_Bar(); - if (process == Print) Draw_Print_Filename(); - } - - static millis_t statustime = 0; - if (ELAPSED(ms, statustime)) { - statustime = ms + 500; - Draw_Status_Area(); - } - - static millis_t printtime = 0; - if (ELAPSED(ms, printtime)) { - printtime = ms + 1000; - if (process == Print) { - Draw_Print_ProgressBar(); - Draw_Print_ProgressElapsed(); - TERN_(USE_M73_REMAINING_TIME, Draw_Print_ProgressRemain()); - } - } - - static bool mounted = card.isMounted(); - if (mounted != card.isMounted()) { - mounted = card.isMounted(); - if (process == File) - Draw_SD_List(); - } - - #if HAS_HOTEND - static int16_t hotendtarget = -1; - #endif - #if HAS_HEATED_BED - static int16_t bedtarget = -1; - #endif - #if HAS_FAN - static int16_t fanspeed = -1; - #endif - - #if HAS_ZOFFSET_ITEM - static float lastzoffset = zoffsetvalue; - if (zoffsetvalue != lastzoffset) { - lastzoffset = zoffsetvalue; - #if HAS_BED_PROBE - probe.offset.z = zoffsetvalue; - #else - set_home_offset(Z_AXIS, -zoffsetvalue); - #endif - } - - #if HAS_BED_PROBE - if (probe.offset.z != lastzoffset) - zoffsetvalue = lastzoffset = probe.offset.z; - #else - if (-home_offset.z != lastzoffset) - zoffsetvalue = lastzoffset = -home_offset.z; - #endif - #endif // HAS_ZOFFSET_ITEM - - if (process == Menu || process == Value) { - switch (active_menu) { - case TempMenu: - #if HAS_HOTEND - if (thermalManager.temp_hotend[0].target != hotendtarget) { - hotendtarget = thermalManager.temp_hotend[0].target; - if (scrollpos <= TEMP_HOTEND && TEMP_HOTEND <= scrollpos + MROWS) { - if (process != Value || selection != TEMP_HOTEND - scrollpos) - Draw_Float(thermalManager.temp_hotend[0].target, TEMP_HOTEND - scrollpos, false, 1); - } - } - #endif - #if HAS_HEATED_BED - if (thermalManager.temp_bed.target != bedtarget) { - bedtarget = thermalManager.temp_bed.target; - if (scrollpos <= TEMP_BED && TEMP_BED <= scrollpos + MROWS) { - if (process != Value || selection != TEMP_HOTEND - scrollpos) - Draw_Float(thermalManager.temp_bed.target, TEMP_BED - scrollpos, false, 1); - } - } - #endif - #if HAS_FAN - if (thermalManager.fan_speed[0] != fanspeed) { - fanspeed = thermalManager.fan_speed[0]; - if (scrollpos <= TEMP_FAN && TEMP_FAN <= scrollpos + MROWS) { - if (process != Value || selection != TEMP_HOTEND - scrollpos) - Draw_Float(thermalManager.fan_speed[0], TEMP_FAN - scrollpos, false, 1); - } - } - #endif - break; - case Tune: - #if HAS_HOTEND - if (thermalManager.temp_hotend[0].target != hotendtarget) { - hotendtarget = thermalManager.temp_hotend[0].target; - if (scrollpos <= TUNE_HOTEND && TUNE_HOTEND <= scrollpos + MROWS) { - if (process != Value || selection != TEMP_HOTEND - scrollpos) - Draw_Float(thermalManager.temp_hotend[0].target, TUNE_HOTEND - scrollpos, false, 1); - } - } - #endif - #if HAS_HEATED_BED - if (thermalManager.temp_bed.target != bedtarget) { - bedtarget = thermalManager.temp_bed.target; - if (scrollpos <= TUNE_BED && TUNE_BED <= scrollpos + MROWS) { - if (process != Value || selection != TEMP_HOTEND - scrollpos) - Draw_Float(thermalManager.temp_bed.target, TUNE_BED - scrollpos, false, 1); - } - } - #endif - #if HAS_FAN - if (thermalManager.fan_speed[0] != fanspeed) { - fanspeed = thermalManager.fan_speed[0]; - if (scrollpos <= TUNE_FAN && TUNE_FAN <= scrollpos + MROWS) { - if (process != Value || selection != TEMP_HOTEND - scrollpos) - Draw_Float(thermalManager.fan_speed[0], TUNE_FAN - scrollpos, false, 1); - } - } - #endif - break; - } - } -} - -void CrealityDWINClass::AudioFeedback(const bool success/*=true*/) { - if (ui.buzzer_enabled) - DONE_BUZZ(success); - else - Update_Status(success ? "Success" : "Failed"); -} - -void CrealityDWINClass::Save_Settings(char *buff) { - TERN_(AUTO_BED_LEVELING_UBL, eeprom_settings.tilt_grid_size = mesh_conf.tilt_grid - 1); - eeprom_settings.corner_pos = corner_pos * 10; - memcpy(buff, &eeprom_settings, _MIN(sizeof(eeprom_settings), eeprom_data_size)); -} - -void CrealityDWINClass::Load_Settings(const char *buff) { - memcpy(&eeprom_settings, buff, _MIN(sizeof(eeprom_settings), eeprom_data_size)); - TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); - if (eeprom_settings.corner_pos == 0) eeprom_settings.corner_pos = 325; - corner_pos = eeprom_settings.corner_pos / 10.0f; - Redraw_Screen(); - #if ENABLED(POWER_LOSS_RECOVERY) - static bool init = true; - if (init) { - init = false; - queue.inject(F("M1000 S")); - } - #endif -} - -void CrealityDWINClass::Reset_Settings() { - eeprom_settings.time_format_textual = false; - TERN_(AUTO_BED_LEVELING_UBL, eeprom_settings.tilt_grid_size = 0); - eeprom_settings.corner_pos = 325; - eeprom_settings.cursor_color = 0; - eeprom_settings.menu_split_line = 0; - eeprom_settings.menu_top_bg = 0; - eeprom_settings.menu_top_txt = 0; - eeprom_settings.highlight_box = 0; - eeprom_settings.progress_percent = 0; - eeprom_settings.progress_time = 0; - eeprom_settings.status_bar_text = 0; - eeprom_settings.status_area_text = 0; - eeprom_settings.coordinates_text = 0; - eeprom_settings.coordinates_split_line = 0; - TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); - corner_pos = eeprom_settings.corner_pos / 10.0f; - TERN_(SOUND_MENU_ITEM, ui.buzzer_enabled = true); - Redraw_Screen(); -} - -void MarlinUI::init_lcd() { - delay(800); - 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) - Encoder_Configuration(); - 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); - } - - DWIN_JPG_ShowAndCache(3); - DWIN_JPG_CacheTo1(Language_English); - CrealityDWIN.Redraw_Screen(); -} - -#if ENABLED(ADVANCED_PAUSE_FEATURE) - void MarlinUI::pause_show_message(const PauseMessage message, const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/) { - switch (message) { - case PAUSE_MESSAGE_INSERT: CrealityDWIN.Confirm_Handler(FilInsert); break; - case PAUSE_MESSAGE_PURGE: - case PAUSE_MESSAGE_OPTION: CrealityDWIN.Popup_Handler(PurgeMore); break; - case PAUSE_MESSAGE_HEAT: CrealityDWIN.Confirm_Handler(HeaterTime); break; - case PAUSE_MESSAGE_WAITING: CrealityDWIN.Draw_Print_Screen(); break; - default: break; - } - } -#endif - -#endif // DWIN_CREALITY_LCD_JYERSUI diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h deleted file mode 100644 index d238d8e24ffa..000000000000 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ /dev/null @@ -1,244 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -/** - * lcd/e3v2/jyersui/dwin.h - */ - -#include "dwin_lcd.h" -#include "../common/dwin_set.h" -#include "../common/dwin_font.h" -#include "../common/dwin_color.h" -#include "../common/encoder.h" -#include "../../../libs/BL24CXX.h" - -#include "../../../inc/MarlinConfigPre.h" - -//#define DWIN_CREALITY_LCD_CUSTOM_ICONS - -enum processID : uint8_t { - Main, Print, Menu, Value, Option, File, Popup, Confirm, Wait -}; - -enum PopupID : uint8_t { - Pause, Stop, Resume, SaveLevel, ETemp, ConfFilChange, PurgeMore, MeshSlot, - Level, Home, MoveWait, Heating, FilLoad, FilChange, TempWarn, Runout, PIDWait, Resuming, ManualProbing, - FilInsert, HeaterTime, UserInput, LevelError, InvalidMesh, UI, Complete -}; - -enum menuID : uint8_t { - MainMenu, - Prepare, - Move, - HomeMenu, - ManualLevel, - ZOffset, - Preheat, - ChangeFilament, - Control, - TempMenu, - PID, - HotendPID, - BedPID, - #if HAS_PREHEAT - #define _PREHEAT_ID(N) Preheat##N, - REPEAT_1(PREHEAT_COUNT, _PREHEAT_ID) - #endif - Motion, - HomeOffsets, - MaxSpeed, - MaxAcceleration, - MaxJerk, - Steps, - Visual, - ColorSettings, - Advanced, - ProbeMenu, - Info, - Leveling, - LevelManual, - LevelView, - MeshViewer, - LevelSettings, - ManualMesh, - UBLMesh, - InfoMain, - Tune, - PreheatHotend -}; - -// Custom icons -#if ENABLED(DWIN_CREALITY_LCD_CUSTOM_ICONS) - // index of every custom icon should be >= CUSTOM_ICON_START - #define CUSTOM_ICON_START ICON_Checkbox_F - #define ICON_Checkbox_F 200 - #define ICON_Checkbox_T 201 - #define ICON_Fade 202 - #define ICON_Mesh 203 - #define ICON_Tilt 204 - #define ICON_Brightness 205 - #define ICON_AxisD 249 - #define ICON_AxisBR 250 - #define ICON_AxisTR 251 - #define ICON_AxisBL 252 - #define ICON_AxisTL 253 - #define ICON_AxisC 254 -#else - #define ICON_Fade ICON_Version - #define ICON_Mesh ICON_Version - #define ICON_Tilt ICON_Version - #define ICON_Brightness ICON_Version - #define ICON_AxisD ICON_Axis - #define ICON_AxisBR ICON_Axis - #define ICON_AxisTR ICON_Axis - #define ICON_AxisBL ICON_Axis - #define ICON_AxisTL ICON_Axis - #define ICON_AxisC ICON_Axis -#endif - -enum colorID : uint8_t { - Default, White, Green, Cyan, Blue, Magenta, Red, Orange, Yellow, Brown, Black -}; - -#define Custom_Colors 10 -#define Color_Aqua RGB(0x00,0x3F,0x1F) -#define Color_Light_White 0xBDD7 -#define Color_Green RGB(0x00,0x3F,0x00) -#define Color_Light_Green 0x3460 -#define Color_Cyan 0x07FF -#define Color_Light_Cyan 0x04F3 -#define Color_Blue 0x015F -#define Color_Light_Blue 0x3A6A -#define Color_Magenta 0xF81F -#define Color_Light_Magenta 0x9813 -#define Color_Light_Red 0x8800 -#define Color_Orange 0xFA20 -#define Color_Light_Orange 0xFBC0 -#define Color_Light_Yellow 0x8BE0 -#define Color_Brown 0xCC27 -#define Color_Light_Brown 0x6204 -#define Color_Black 0x0000 -#define Color_Grey 0x18E3 -#define Check_Color 0x4E5C // Check-box check color -#define Confirm_Color 0x34B9 -#define Cancel_Color 0x3186 - -class CrealityDWINClass { -public: - static constexpr size_t eeprom_data_size = 48; - static struct EEPROM_Settings { // use bit fields to save space, max 48 bytes - bool time_format_textual : 1; - #if ENABLED(AUTO_BED_LEVELING_UBL) - uint8_t tilt_grid_size : 3; - #endif - uint16_t corner_pos : 10; - uint8_t cursor_color : 4; - uint8_t menu_split_line : 4; - uint8_t menu_top_bg : 4; - uint8_t menu_top_txt : 4; - uint8_t highlight_box : 4; - uint8_t progress_percent : 4; - uint8_t progress_time : 4; - uint8_t status_bar_text : 4; - uint8_t status_area_text : 4; - uint8_t coordinates_text : 4; - uint8_t coordinates_split_line : 4; - } eeprom_settings; - - static constexpr const char * const color_names[11] = { "Default", "White", "Green", "Cyan", "Blue", "Magenta", "Red", "Orange", "Yellow", "Brown", "Black" }; - static constexpr const char * const preheat_modes[3] = { "Both", "Hotend", "Bed" }; - - static void Clear_Screen(uint8_t e=3); - static void Draw_Float(float value, uint8_t row, bool selected=false, uint8_t minunit=10); - static void Draw_Option(uint8_t value, const char * const * options, uint8_t row, bool selected=false, bool color=false); - static uint16_t GetColor(uint8_t color, uint16_t original, bool light=false); - static void Draw_Checkbox(uint8_t row, bool value); - static void Draw_Title(const char * title); - static void Draw_Title(FSTR_P const title); - static void Draw_Menu_Item(uint8_t row, uint8_t icon=0, const char * const label1=nullptr, const char * const label2=nullptr, bool more=false, bool centered=false); - static void Draw_Menu_Item(uint8_t row, uint8_t icon=0, FSTR_P const flabel1=nullptr, FSTR_P const flabel2=nullptr, bool more=false, bool centered=false); - static void Draw_Menu(uint8_t menu, uint8_t select=0, uint8_t scroll=0); - static void Redraw_Menu(bool lastprocess=true, bool lastselection=false, bool lastmenu=false); - static void Redraw_Screen(); - - static void Main_Menu_Icons(); - static void Draw_Main_Menu(uint8_t select=0); - static void Print_Screen_Icons(); - static void Draw_Print_Screen(); - static void Draw_Print_Filename(const bool reset=false); - static void Draw_Print_ProgressBar(); - #if ENABLED(USE_M73_REMAINING_TIME) - static void Draw_Print_ProgressRemain(); - #endif - static void Draw_Print_ProgressElapsed(); - static void Draw_Print_confirm(); - static void Draw_SD_Item(uint8_t item, uint8_t row); - static void Draw_SD_List(bool removed=false); - static void Draw_Status_Area(bool icons=false); - static void Draw_Popup(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, uint8_t mode, uint8_t icon=0); - static void Popup_Select(); - static void Update_Status_Bar(bool refresh=false); - - #if ENABLED(AUTO_BED_LEVELING_UBL) - static void Draw_Bed_Mesh(int16_t selected = -1, uint8_t gridline_width = 1, uint16_t padding_x = 8, uint16_t padding_y_top = 40 + 53 - 7); - static void Set_Mesh_Viewer_Status(); - #endif - - static FSTR_P Get_Menu_Title(uint8_t menu); - static uint8_t Get_Menu_Size(uint8_t menu); - static void Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw=true); - - static void Popup_Handler(PopupID popupid, bool option = false); - static void Confirm_Handler(PopupID popupid); - - static void Main_Menu_Control(); - static void Menu_Control(); - static void Value_Control(); - static void Option_Control(); - static void File_Control(); - static void Print_Screen_Control(); - static void Popup_Control(); - static void Confirm_Control(); - - static void Setup_Value(float value, float min, float max, float unit, uint8_t type); - static void Modify_Value(float &value, float min, float max, float unit, void (*f)()=nullptr); - static void Modify_Value(uint8_t &value, float min, float max, float unit, void (*f)()=nullptr); - static void Modify_Value(uint16_t &value, float min, float max, float unit, void (*f)()=nullptr); - static void Modify_Value(int16_t &value, float min, float max, float unit, void (*f)()=nullptr); - static void Modify_Value(uint32_t &value, float min, float max, float unit, void (*f)()=nullptr); - static void Modify_Value(int8_t &value, float min, float max, float unit, void (*f)()=nullptr); - static void Modify_Option(uint8_t value, const char * const * options, uint8_t max); - - static void Update_Status(const char * const text); - static void Start_Print(bool sd); - static void Stop_Print(); - static void Update(); - static void State_Update(); - static void Screen_Update(); - static void AudioFeedback(const bool success=true); - static void Save_Settings(char *buff); - static void Load_Settings(const char *buff); - static void Reset_Settings(); -}; - -extern CrealityDWINClass CrealityDWIN; diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp deleted file mode 100644 index 04889e92b038..000000000000 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp +++ /dev/null @@ -1,64 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -/******************************************************************************** - * @file lcd/e3v2/jyersui/dwin_lcd.cpp - * @brief DWIN screen control functions - ********************************************************************************/ - -#include "../../../inc/MarlinConfigPre.h" - -#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) - -#include "dwin_lcd.h" - -/*-------------------------------------- System variable function --------------------------------------*/ - -void DWIN_Startup() {} - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Draw the degree (°) symbol -// Color: color -// x/y: Upper-left coordinate of the first pixel -void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y) { - DWIN_Draw_Point(Color, 1, 1, x + 1, y); - DWIN_Draw_Point(Color, 1, 1, x + 2, y); - DWIN_Draw_Point(Color, 1, 1, x, y + 1); - DWIN_Draw_Point(Color, 1, 1, x + 3, y + 1); - DWIN_Draw_Point(Color, 1, 1, x, y + 2); - DWIN_Draw_Point(Color, 1, 1, x + 3, y + 2); - DWIN_Draw_Point(Color, 1, 1, x + 1, y + 3); - DWIN_Draw_Point(Color, 1, 1, x + 2, y + 3); -} - -/*---------------------------------------- Picture related functions ----------------------------------------*/ - -// 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) { - DWIN_ICON_Show(true, false, false, libID, picID, x, y); -} - -#endif // DWIN_CREALITY_LCD_JYERSUI diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h deleted file mode 100644 index f76cfb5d3e5f..000000000000 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h +++ /dev/null @@ -1,34 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -/******************************************************************************** - * @file lcd/e3v2/jyersui/dwin_lcd.h - * @brief DWIN screen control functions - ********************************************************************************/ - -#include "../common/dwin_api.h" - -// Draw the degree (°) symbol -// Color: color -// x/y: Upper-left coordinate of the first pixel -void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y); diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp index e2d4d62c771e..38a8eafe2366 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp @@ -27,35 +27,35 @@ #include "dwin_string.h" //#include "../../fontutils.h" -uint8_t DWIN_String::data[]; +char DWIN_String::data[]; uint16_t DWIN_String::span; -uint8_t DWIN_String::len; +uint8_t DWIN_String::length; void DWIN_String::set() { //*data = 0x00; memset(data, 0x00, sizeof(data)); span = 0; - len = 0; + length = 0; } -uint8_t read_byte(uint8_t *byte) { return *byte; } +uint8_t read_byte(const uint8_t *byte) { return *byte; } /** * Add a string, applying substitutions for the following characters: * - * $ displays the clipped C-string given by the itemString argument + * $ displays the clipped string given by fstr or cstr * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder */ -void DWIN_String::add(uint8_t *string, const int8_t index, uint8_t *itemString/*=nullptr*/) { - wchar_t wchar; +void DWIN_String::add(const char *tpl, const int8_t index, const char *cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/) { + lchar_t wc; - while (*string) { - string = get_utf8_value_cb(string, read_byte, &wchar); - if (wchar > 255) wchar |= 0x0080; - uint8_t ch = uint8_t(wchar & 0x00FF); + while (*tpl) { + tpl = get_utf8_value_cb(tpl, read_byte, wc); + if (wc > 255) wc |= 0x0080; + const uint8_t ch = uint8_t(wc & 0x00FF); if (ch == '=' || ch == '~' || ch == '*') { if (index >= 0) { @@ -65,10 +65,12 @@ void DWIN_String::add(uint8_t *string, const int8_t index, uint8_t *itemString/* add_character('0' + inum); } else - add(index == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED)); + add(index == -2 ? GET_TEXT_F(MSG_CHAMBER) : GET_TEXT_F(MSG_BED)); } - else if (ch == '$' && itemString) - add(itemString); + else if (ch == '$' && fstr) + add(fstr); + else if (ch == '$' && cstr) + add(cstr); else if (ch == '@') add_character(AXIS_CHAR(index)); else @@ -77,33 +79,33 @@ void DWIN_String::add(uint8_t *string, const int8_t index, uint8_t *itemString/* eol(); } -void DWIN_String::add(uint8_t *string, uint8_t max_len) { - wchar_t wchar; - while (*string && max_len) { - string = get_utf8_value_cb(string, read_byte, &wchar); +void DWIN_String::add(const char *cstr, uint8_t max_len/*=MAX_STRING_LENGTH*/) { + lchar_t wc; + while (*cstr && max_len) { + cstr = get_utf8_value_cb(cstr, read_byte, wc); /* - if (wchar > 255) wchar |= 0x0080; - uint8_t ch = uint8_t(wchar & 0x00FF); + if (wc > 255) wc |= 0x0080; + const uint8_t ch = uint8_t(wc & 0x00FF); add_character(ch); */ - add(wchar); + add(wc); max_len--; } eol(); } -void DWIN_String::add(wchar_t character) { +void DWIN_String::add(const lchar_t &wc) { int ret; size_t idx = 0; dwin_charmap_t pinval; dwin_charmap_t *copy_address = nullptr; - pinval.uchar = character; + pinval.uchar = wc; pinval.idx = -1; // For 8-bit ASCII just print the single character char str[] = { '?', 0 }; - if (character < 255) { - str[0] = (char)character; + if (wc < 255) { + str[0] = (char)wc; } else { copy_address = nullptr; @@ -127,18 +129,18 @@ void DWIN_String::add(wchar_t character) { if (str[1]) add_character(str[1]); } -void DWIN_String::add_character(const uint8_t character) { - if (len < MAX_STRING_LENGTH) { - data[len] = character; - len++; +void DWIN_String::add_character(const char character) { + if (length < MAX_STRING_LENGTH) { + data[length] = character; + length++; //span += glyph(character)->DWidth; } } -void DWIN_String::rtrim(const uint8_t character) { - while (len) { - if (data[len - 1] == 0x20 || data[len - 1] == character) { - len--; +void DWIN_String::rtrim(const char character) { + while (length) { + if (data[length - 1] == 0x20 || data[length - 1] == character) { + length--; //span -= glyph(data[length])->DWidth; eol(); } @@ -147,18 +149,18 @@ void DWIN_String::rtrim(const uint8_t character) { } } -void DWIN_String::ltrim(const uint8_t character) { +void DWIN_String::ltrim(const char character) { uint16_t i, j; - for (i = 0; (i < len) && (data[i] == 0x20 || data[i] == character); i++) { + for (i = 0; (i < length) && (data[i] == 0x20 || data[i] == character); i++) { //span -= glyph(data[i])->DWidth; } if (i == 0) return; - for (j = 0; i < len; data[j++] = data[i++]); - len = j; + for (j = 0; i < length; data[j++] = data[i++]); + length = j; eol(); } -void DWIN_String::trim(const uint8_t character) { +void DWIN_String::trim(const char character) { rtrim(character); ltrim(character); } diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h index 64676dddfdaf..686b1aa2b17a 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -21,13 +21,15 @@ */ #pragma once +// TODO: Make AVR-compatible with separate ROM / RAM string methods + #include "../../fontutils.h" #include "../../marlinui.h" #include typedef struct _dwin_charmap_t { - wchar_t uchar; // the unicode char + lchar_t uchar; // the unicode char uint8_t idx; // the glyph of the char in the ROM uint8_t idx2; // the char used to be combined with the idx to simulate a single char } dwin_charmap_t; @@ -41,14 +43,14 @@ class DWIN_String { //static glyph_t *glyphs[256]; //static font_t *font_header; - static uint8_t data[MAX_STRING_LENGTH + 1]; + static char data[MAX_STRING_LENGTH + 1]; static uint16_t span; // in pixels - static uint8_t len; // in characters - static void add_character(const uint8_t character); - static void eol() { data[len] = 0x00; } + static void add_character(const char character); + static void eol() { data[length] = 0x00; } public: + static uint8_t length; // in characters //static void set_font(const uint8_t *font); //static void add_glyphs(const uint8_t *font); @@ -57,29 +59,71 @@ class DWIN_String { //static glyph_t *glyph(uint8_t character) { return glyphs[character] ?: glyphs[0x3F]; } /* Use '?' for unknown glyphs */ //static glyph_t *glyph(uint8_t *character) { return glyph(*character); } + /** + * @brief Set the string empty + */ static void set(); - //static void add(uint8_t character) { add_character(character); eol(); } - static void add(wchar_t character); - static void add(uint8_t *string, uint8_t max_len=MAX_STRING_LENGTH); - static void add(uint8_t *string, const int8_t index, uint8_t *itemString=nullptr); - static void set(uint8_t *string) { set(); add(string); } - static void set(wchar_t character) { set(); add(character); } - static void set(uint8_t *string, int8_t index, const char *itemString=nullptr) { set(); add(string, index, (uint8_t *)itemString); } - static void set(FSTR_P fstring) { set((uint8_t *)fstring); } - static void set(const char *string) { set((uint8_t *)string); } - static void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } - static void add(const char *string) { add((uint8_t *)string); } - - static void trim(const uint8_t character=0x20); - static void rtrim(const uint8_t character=0x20); - static void ltrim(const uint8_t character=0x20); - - static void truncate(uint8_t maxlen) { if (len > maxlen) { len = maxlen; eol(); } } - - static uint8_t length() { return len; } + + //static void add(const char character) { add_character(character); eol(); } + + /** + * @brief Append a UTF-8 character + * + * @param wc The UTF-8 character + */ + static void add(const lchar_t &wc); + static void set(const lchar_t &wc) { set(); add(wc); } + + /** + * @brief Append / Set C-string + * + * @param cstr The string + * @param max_len Character limit + */ + static void add(const char *cstr, uint8_t max_len=MAX_STRING_LENGTH); + static void set(const char *cstr) { set(); add(cstr); } + + /** + * @brief Append / Set F-string + * + * @param fstr The string + * @param max_len Character limit + */ + static void add(FSTR_P const fstr, uint8_t max_len=MAX_STRING_LENGTH) { add(FTOP(fstr), max_len); } + static void set(FSTR_P const fstr) { set(FTOP(fstr)); } + + /** + * @brief Append / Set C-string with optional substitution + * + * @param tpl A string with optional substitution + * @param index An index + * @param cstr An SRAM C-string to use for $ substitution + * @param fstr A ROM F-string to use for $ substitution + */ + static void add(const char *tpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr); + static void set(const char *tpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { set(); add(tpl, index, cstr, fstr); } + + /** + * @brief Append / Set F-string with optional substitution + * + * @param ftpl A ROM F-string with optional substitution + * @param index An index + * @param cstr An SRAM C-string to use for $ substitution + * @param fstr A ROM F-string to use for $ substitution + */ + static void add(FSTR_P const ftpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { add(FTOP(ftpl), index, cstr, fstr); } + static void set(FSTR_P const ftpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { set(); add(ftpl, index, cstr, fstr); } + + // Common string ops + static void trim(const char character=' '); + static void rtrim(const char character=' '); + static void ltrim(const char character=' '); + static void truncate(const uint8_t maxlen) { if (length > maxlen) { length = maxlen; eol(); } } + + // Accessors + static char *string() { return data; } 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; } + static uint16_t center(const uint16_t width) { return span > width ? 0 : (width - span) / 2; } }; int dwin_charmap_compare(dwin_charmap_t *v1, dwin_charmap_t *v2); diff --git a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp index 44be749d41fc..e603882e0cfd 100644 --- a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp @@ -56,20 +56,20 @@ void lcd_put_int(const int i) { } int lcd_put_dwin_string() { - DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); - lcd_advance_cursor(dwin_string.length()); - return dwin_string.length(); + DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, dwin_string.string()); + lcd_advance_cursor(dwin_string.length); + return dwin_string.length; } // return < 0 on error // return the advanced cols -int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { +int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { dwin_string.set(c); dwin_string.truncate(max_length); // Draw the char(s) at the cursor and advance the cursor - DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); - lcd_advance_cursor(dwin_string.length()); - return dwin_string.length(); + DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, dwin_string.string()); + lcd_advance_cursor(dwin_string.length); + return dwin_string.length; } /** @@ -83,35 +83,34 @@ int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { * * Draw a UTF-8 string */ -static int lcd_put_u8str_max_cb(const char * utf8_str, uint8_t (*cb_read_byte)(uint8_t * str), pixel_len_t max_length) { - uint8_t *p = (uint8_t *)utf8_str; +static int lcd_put_u8str_max_cb(const char * utf8_str, read_byte_cb_t cb_read_byte, const pixel_len_t max_length) { + const uint8_t *p = (uint8_t *)utf8_str; dwin_string.set(); - while (dwin_string.length() < max_length) { - wchar_t ch = 0; - p = get_utf8_value_cb(p, cb_read_byte, &ch); - if (!ch) break; - dwin_string.add(ch); + while (dwin_string.length < max_length) { + lchar_t wc; + p = get_utf8_value_cb(p, cb_read_byte, wc); + if (!wc) break; + dwin_string.add(wc); } - DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); - lcd_advance_cursor(dwin_string.length()); - return dwin_string.length(); + DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, dwin_string.string()); + lcd_advance_cursor(dwin_string.length); + return dwin_string.length; } -int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { +int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); } -int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P utf8_pstr, const pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_pstr, read_byte_rom, max_length); } -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*/) { - dwin_string.set(); - dwin_string.add((uint8_t*)pstr, ind, (uint8_t*)inStr); +lcd_uint_t lcd_put_u8str_P(PGM_P const ptpl, const int8_t ind, const char * const cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { + dwin_string.set(ptpl, ind, cstr, fstr); dwin_string.truncate(maxlen); - DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); - lcd_advance_cursor(dwin_string.length()); - return dwin_string.length(); + DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, dwin_string.string()); + lcd_advance_cursor(dwin_string.length); + return dwin_string.length; } #if ENABLED(DEBUG_LCDPRINT) diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index 1730e6832759..455fce272a1c 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -110,7 +110,7 @@ void MarlinUI::clear_lcd() { #define VERSION_Y 84 #endif - DWIN_Draw_String(false, font10x20, Color_Yellow, Color_Bg_Black, INFO_CENTER - (dwin_string.length() * 10) / 2, VERSION_Y, S(dwin_string.string())); + DWIN_Draw_String(false, font10x20, Color_Yellow, Color_Bg_Black, INFO_CENTER - (dwin_string.length * 10) / 2, VERSION_Y, S(dwin_string.string())); TERN_(SHOW_CUSTOM_BOOTSCREEN, safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT)); clear_lcd(); @@ -127,7 +127,7 @@ void MarlinUI::clear_lcd() { DWIN_ICON_Show(BOOT_ICON, ICON_MarlinURL, INFO_CENTER - 100 / 2, 152); DWIN_ICON_Show(BOOT_ICON, ICON_Copyright, INFO_CENTER - 126 / 2, 200); #endif - DWIN_Draw_String(false, font10x20, Color_Yellow, Color_Bg_Black, INFO_CENTER - (dwin_string.length() * 10) / 2, VERSION_Y, S(dwin_string.string())); + DWIN_Draw_String(false, font10x20, Color_Yellow, Color_Bg_Black, INFO_CENTER - (dwin_string.length * 10) / 2, VERSION_Y, S(dwin_string.string())); DWIN_UpdateLCD(); } @@ -213,7 +213,7 @@ void MarlinUI::draw_status_message(const bool blink) { lcd_put_u8str(status_message); // Fill the rest with spaces - while (slen < max_status_chars) { lcd_put_wchar(' '); ++slen; } + while (slen < max_status_chars) { lcd_put_lchar(' '); ++slen; } } } else { @@ -227,10 +227,10 @@ void MarlinUI::draw_status_message(const bool blink) { // If the string doesn't completely fill the line... if (rlen < max_status_chars) { - lcd_put_wchar('.'); // Always at 1+ spaces left, draw a dot + lcd_put_lchar('.'); // Always at 1+ spaces left, draw a dot uint8_t chars = max_status_chars - rlen; // Amount of space left in characters if (--chars) { // Draw a second dot if there's space - lcd_put_wchar('.'); + lcd_put_lchar('.'); if (--chars) lcd_put_u8str_max(status_message, chars); // Print a second copy of the message } @@ -254,7 +254,7 @@ void MarlinUI::draw_status_message(const bool blink) { lcd_put_u8str_max(status_message, max_status_chars); // Fill the rest with spaces if there are missing spaces - while (slen < max_status_chars) { lcd_put_wchar(' '); ++slen; } + while (slen < max_status_chars) { lcd_put_lchar(' '); ++slen; } } #endif @@ -274,7 +274,7 @@ void MarlinUI::draw_status_message(const bool blink) { dwin_font.solid = false; dwin_font.fg = Color_White; - dwin_string.set("E"); + dwin_string.set('E'); dwin_string.add('1' + extruder); dwin_string.add(' '); dwin_string.add(i16tostr3rj(thermalManager.degHotend(extruder))); @@ -282,9 +282,9 @@ void MarlinUI::draw_status_message(const bool blink) { if (get_blink() || !thermalManager.heater_idle[thermalManager.idle_index_for_id(extruder)].timed_out) dwin_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder))); else - dwin_string.add(PSTR(" ")); + dwin_string.add(F(" ")); - lcd_moveto(LCD_WIDTH - dwin_string.length(), row); + lcd_moveto(LCD_WIDTH - dwin_string.length, row); lcd_put_dwin_string(); } @@ -311,7 +311,7 @@ void MarlinUI::draw_status_message(const bool blink) { // 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*/) { + void MenuItem_static::draw(const uint8_t row, FSTR_P const ftpl, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { // Call mark_as_selected to draw a bigger selection box // and draw the text without a background if (mark_as_selected(row, (bool)(style & SS_INVERT), true)) { @@ -320,15 +320,15 @@ void MarlinUI::draw_status_message(const bool blink) { dwin_font.fg = Color_White; dwin_string.set(); - const int8_t plen = pstr ? utf8_strlen_P(pstr) : 0, + const int8_t plen = ftpl ? utf8_strlen(ftpl) : 0, vlen = vstr ? utf8_strlen(vstr) : 0; if (style & SS_CENTER) { int8_t pad = (LCD_WIDTH - 1 - plen - vlen) / 2; while (--pad) dwin_string.add(' '); } - if (plen) dwin_string.add((uint8_t*)pstr, itemIndex, (uint8_t*)itemString); - if (vlen) dwin_string.add((uint8_t*)vstr); + if (plen) dwin_string.add(ftpl, itemIndex, itemStringC, itemStringF); + if (vlen) dwin_string.add(vstr); if (style & SS_CENTER) { int8_t pad = (LCD_WIDTH - 1 - plen - vlen) / 2; while (--pad) dwin_string.add(' '); @@ -340,15 +340,15 @@ void MarlinUI::draw_status_message(const bool blink) { } // 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) { + void MenuItemBase::_draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char, const char post_char) { if (mark_as_selected(row, sel)) { ui.set_font(DWIN_FONT_MENU); dwin_font.solid = false; dwin_font.fg = Color_White; - dwin_string.set(pstr, itemIndex, itemString); + dwin_string.set(ftpl, itemIndex, itemStringC, itemStringF); - pixel_len_t n = LCD_WIDTH - 1 - dwin_string.length(); + pixel_len_t n = LCD_WIDTH - 1 - dwin_string.length; while (--n > 1) dwin_string.add(' '); dwin_string.add(post_char); @@ -361,15 +361,15 @@ void MarlinUI::draw_status_message(const bool blink) { // // 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 data, const bool pgm) { + void MenuEditItemBase::draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char * const inStr, const bool pgm) { if (mark_as_selected(row, sel)) { ui.set_font(DWIN_FONT_MENU); dwin_font.solid = false; dwin_font.fg = Color_White; - const uint8_t vallen = (pgm ? utf8_strlen_P(data) : utf8_strlen(S(data))); + const uint8_t vallen = (pgm ? utf8_strlen_P(inStr) : utf8_strlen(S(inStr))); - dwin_string.set(pstr, itemIndex, itemString); + dwin_string.set(ftpl, itemIndex, itemStringC, itemStringF); if (vallen) dwin_string.add(':'); lcd_moveto(1, row); @@ -377,7 +377,7 @@ void MarlinUI::draw_status_message(const bool blink) { if (vallen) { dwin_font.fg = Color_Yellow; - dwin_string.set(data); + dwin_string.set(inStr); lcd_moveto(LCD_WIDTH - vallen - 1, row); lcd_put_dwin_string(); } @@ -387,13 +387,12 @@ void MarlinUI::draw_status_message(const bool blink) { // // Draw an edit screen with label and current value // - void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) { + void MenuEditItemBase::draw_edit_screen(FSTR_P const fstr, const char* const value/*=nullptr*/) { ui.encoder_direction_normal(); - const dwin_coord_t labellen = utf8_strlen_P(pstr), vallen = utf8_strlen(value); + const dwin_coord_t labellen = utf8_strlen(fstr), vallen = utf8_strlen(value); - dwin_string.set(); - dwin_string.add((uint8_t*)pstr, itemIndex); + dwin_string.set(FTOP(fstr), itemIndex); if (vallen) dwin_string.add(':'); // If a value is included, add a colon // Assume the label is alpha-numeric (with a descender) @@ -406,14 +405,12 @@ void MarlinUI::draw_status_message(const bool blink) { // If a value is included, print the value in larger text below the label if (vallen) { - dwin_string.set(); - dwin_string.add(value); + dwin_string.set(value); const dwin_coord_t by = (row * MENU_LINE_HEIGHT) + MENU_FONT_HEIGHT + EXTRA_ROW_HEIGHT / 2; DWIN_Draw_String(true, font16x32, Color_Yellow, Color_Bg_Black, (LCD_PIXEL_WIDTH - vallen * 16) / 2, by, S(dwin_string.string())); - extern screenFunc_t _manual_move_func_ptr; - if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { + if (ui.can_show_slider()) { const dwin_coord_t slider_length = LCD_PIXEL_WIDTH - TERN(DWIN_MARLINUI_LANDSCAPE, 120, 20), slider_height = 16, @@ -430,19 +427,19 @@ void MarlinUI::draw_status_message(const bool blink) { } } - inline void draw_boxed_string(const bool yesopt, PGM_P const pstr, const bool inv) { - const uint8_t len = utf8_strlen_P(pstr), + inline void draw_boxed_string(const bool yesopt, FSTR_P const fstr, const bool inv) { + const uint8_t len = utf8_strlen(fstr), mar = TERN(DWIN_MARLINUI_PORTRAIT, 1, 4), col = yesopt ? LCD_WIDTH - mar - len : mar, row = (LCD_HEIGHT >= 8 ? LCD_HEIGHT / 2 + 3 : LCD_HEIGHT - 1); lcd_moveto(col, row); DWIN_Draw_Box(1, inv ? Select_Color : Color_Bg_Black, cursor.x - dwin_font.width, cursor.y + 1, dwin_font.width * (len + 2), dwin_font.height + 2); - lcd_put_u8str_P(col, row, pstr); + lcd_put_u8str(col, row, fstr); } 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*/ + FSTR_P const yes, FSTR_P const no, const bool yesno, + FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/ ) { ui.set_font(DWIN_FONT_MENU); dwin_font.solid = false; @@ -454,7 +451,7 @@ void MarlinUI::draw_status_message(const bool blink) { #if ENABLED(SDSUPPORT) - void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { if (mark_as_selected(row, sel)) { dwin_string.set(); @@ -464,8 +461,8 @@ void MarlinUI::draw_status_message(const bool blink) { maxlen -= 2; } - dwin_string.add((uint8_t*)ui.scrolled_filename(theCard, maxlen, row, sel), maxlen); - uint8_t n = maxlen - dwin_string.length(); + dwin_string.add(ui.scrolled_filename(theCard, maxlen, row, sel), maxlen); + uint8_t n = maxlen - dwin_string.length; while (n > 0) { dwin_string.add(' '); --n; } lcd_moveto(1, row); lcd_put_dwin_string(); @@ -516,8 +513,8 @@ void MarlinUI::draw_status_message(const bool blink) { // Display Mesh Point Locations const dwin_coord_t sx = x_offset + pixels_per_x_mesh_pnt / 2; dwin_coord_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) - for (uint8_t i = 0, x = sx; i < GRID_MAX_POINTS_X; i++, x += pixels_per_x_mesh_pnt) + for (uint8_t j = 0; j < (GRID_MAX_POINTS_Y); j++, y += pixels_per_y_mesh_pnt) + for (uint8_t i = 0, x = sx; i < (GRID_MAX_POINTS_X); i++, x += pixels_per_x_mesh_pnt) DWIN_Draw_Point(Color_White, 1, 1, x, y); // Put Relevant Text on Display @@ -525,7 +522,7 @@ void MarlinUI::draw_status_message(const bool blink) { // Show X and Y positions at top of screen dwin_font.fg = Color_White; dwin_font.solid = true; - const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, + const xy_pos_t pos = { bedlevel.get_mesh_x(x_plot), bedlevel.get_mesh_y(y_plot) }, lpos = pos.asLogical(); lcd_moveto( @@ -542,25 +539,25 @@ void MarlinUI::draw_status_message(const bool blink) { lcd_put_u8str(ftostr52(lpos.y)); // Print plot position - dwin_string.set("("); + dwin_string.set('('); dwin_string.add(i8tostr3rj(x_plot)); - dwin_string.add(","); + dwin_string.add(','); dwin_string.add(i8tostr3rj(y_plot)); - dwin_string.add(")"); + dwin_string.add(')'); lcd_moveto( - TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, LCD_WIDTH - dwin_string.length()), + TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, LCD_WIDTH - dwin_string.length), TERN(DWIN_MARLINUI_LANDSCAPE, LCD_HEIGHT - 2, ((y_offset + y_map_pixels) / MENU_LINE_HEIGHT) + 1) ); lcd_put_dwin_string(); // Show the location value dwin_string.set(Z_LBL); - if (!isnan(Z_VALUES_ARR[x_plot][y_plot])) - dwin_string.add(ftostr43sign(Z_VALUES_ARR[x_plot][y_plot])); + if (!isnan(bedlevel.z_values[x_plot][y_plot])) + dwin_string.add(ftostr43sign(bedlevel.z_values[x_plot][y_plot])); else - dwin_string.add(PSTR(" -----")); + dwin_string.add(F(" -----")); lcd_moveto( - TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, LCD_WIDTH - dwin_string.length()), + TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, LCD_WIDTH - dwin_string.length), TERN(DWIN_MARLINUI_LANDSCAPE, LCD_HEIGHT - 1, ((y_offset + y_map_pixels) / MENU_LINE_HEIGHT) + 2) ); lcd_put_dwin_string(); diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp index ba6814a57a10..8024085ef734 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp @@ -72,32 +72,30 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const uint8_t vallen = utf8_strlen(value); if (!ui.did_first_redraw) { - dwin_string.set(); - dwin_string.add('X' + axis); + dwin_string.set('X' + axis); DWIN_Draw_String(true, font16x32, Color_IconBlue, Color_Bg_Black, x + (vallen * 14 - 14) / 2, y + 2, S(dwin_string.string())); } dwin_string.set(); if (blink) dwin_string.add(value); - else if (!TEST(axis_homed, axis)) + else if (!TEST(axes_homed, axis)) while (const char c = *value++) dwin_string.add(c <= '.' ? c : '?'); - else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !TEST(axis_trusted, axis)) + else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !TEST(axes_trusted, axis)) dwin_string.add(TERN1(DWIN_MARLINUI_PORTRAIT, axis == Z_AXIS) ? PSTR(" ") : PSTR(" ")); else dwin_string.add(value); // For E_TOTAL there may be some characters to cover up if (BOTH(DWIN_MARLINUI_PORTRAIT, LCD_SHOW_E_TOTAL) && axis == X_AXIS) - dwin_string.add(" "); + dwin_string.add(F(" ")); DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + 32, S(dwin_string.string())); #else // !DWIN_MARLINUI_PORTRAIT if (!ui.did_first_redraw || ui.old_is_printing != print_job_timer.isRunning()) { - dwin_string.set(); - dwin_string.add('X' + axis); + dwin_string.set('X' + axis); DWIN_Draw_String(true, font16x32, Color_IconBlue, Color_Bg_Black, x, y, S(dwin_string.string())); } @@ -105,11 +103,11 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const if (blink) dwin_string.add(value); else { - if (!TEST(axis_homed, axis)) + if (!TEST(axes_homed, axis)) while (const char c = *value++) dwin_string.add(c <= '.' ? c : '?'); else { #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) - if (!TEST(axis_trusted, axis)) + if (!TEST(axes_trusted, axis)) dwin_string.add(TERN1(DWIN_MARLINUI_PORTRAIT, axis == Z_AXIS) ? PSTR(" ") : PSTR(" ")); else #endif @@ -119,7 +117,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const // For E_TOTAL there may be some characters to cover up if (ENABLED(LCD_SHOW_E_TOTAL) && (!ui.did_first_redraw || ui.old_is_printing != print_job_timer.isRunning()) && axis == X_AXIS) - dwin_string.add(" "); + dwin_string.add(F(" ")); DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x + 32, y + 4, S(dwin_string.string())); @@ -135,7 +133,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const if (!ui.did_first_redraw) { // Extra spaces to erase previous value - dwin_string.set("E "); + dwin_string.set(F("E ")); DWIN_Draw_String(true, font16x32, Color_IconBlue, Color_Bg_Black, x + (4 * 14 / 2) - 7, y + 2, S(dwin_string.string())); } @@ -148,7 +146,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #else // !DWIN_MARLINUI_PORTRAIT if (!ui.did_first_redraw || ui.old_is_printing != print_job_timer.isRunning()) { - dwin_string.set("E "); + dwin_string.set(F("E ")); DWIN_Draw_String(true, font16x32, Color_IconBlue, Color_Bg_Black, x, y, S(dwin_string.string())); } @@ -178,7 +176,7 @@ FORCE_INLINE void _draw_fan_status(const uint16_t x, const uint16_t y) { else { DWIN_ICON_AnimationControl(0x0000); // disable all icon animations (this is the only one) DWIN_ICON_Show(ICON, ICON_Fan0, x + fanx, y); - dwin_string.set(PSTR(" ")); + dwin_string.set(F(" ")); DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + STATUS_FAN_HEIGHT, S(dwin_string.string())); } } @@ -291,7 +289,7 @@ FORCE_INLINE void _draw_feedrate_status(const char *value, uint16_t x, uint16_t } dwin_string.set(value); - dwin_string.add(PSTR("%")); + dwin_string.add('%'); DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x + 14, y, S(dwin_string.string())); } @@ -391,14 +389,14 @@ void MarlinUI::draw_status_screen() { time.toDigital(buffer); dwin_string.add(prefix); dwin_string.add(buffer); - DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, (LCD_PIXEL_WIDTH - ((dwin_string.length() + 1) * 14)), 290, S(dwin_string.string())); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, (LCD_PIXEL_WIDTH - ((dwin_string.length + 1) * 14)), 290, S(dwin_string.string())); #else // landscape mode shows both elapsed and remaining (if SHOW_REMAINING_TIME) time = print_job_timer.duration(); time.toDigital(buffer); - dwin_string.set(" "); + dwin_string.set(' '); dwin_string.add(buffer); DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, 230, 170, S(dwin_string.string())); @@ -407,7 +405,7 @@ void MarlinUI::draw_status_screen() { time = get_remaining_time(); DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, 336, 170, S(" R ")); if (print_job_timer.isPaused() && blink) - dwin_string.set(" "); + dwin_string.set(F(" ")); else { time.toDigital(buffer); dwin_string.set(buffer); @@ -415,7 +413,7 @@ void MarlinUI::draw_status_screen() { DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, 378, 170, S(dwin_string.string())); } else if (!ui.did_first_redraw || ui.old_is_printing != print_job_timer.isRunning()) { - dwin_string.set(" "); + dwin_string.set(F(" ")); DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, 336, 170, S(dwin_string.string())); } #endif @@ -451,10 +449,10 @@ void MarlinUI::draw_status_screen() { #if ENABLED(SHOW_SD_PERCENT) dwin_string.set(TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(progress), ui8tostr3rj(progress / (PROGRESS_SCALE)))); - dwin_string.add(PSTR("%")); + dwin_string.add('%'); DWIN_Draw_String( false, font16x32, Percent_Color, Color_Bg_Black, - pb_left + (pb_width - dwin_string.length() * 16) / 2, + pb_left + (pb_width - dwin_string.length * 16) / 2, pb_top + (pb_height - 32) / 2, S(dwin_string.string()) ); diff --git a/Marlin/src/lcd/e3v2/proui/base64.hpp b/Marlin/src/lcd/e3v2/proui/base64.hpp new file mode 100644 index 000000000000..d82d0b27e8ac --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/base64.hpp @@ -0,0 +1,208 @@ +/** + * Base64 encoder/decoder for arduino repo + * Uses common web conventions - '+' for 62, '/' for 63, '=' for padding. + * Note that invalid base64 characters are interpreted as padding. + * Author: Densaugeo + * Maintainer: Densaugeo + * Version: 1.2.1.1 + * Changed unsigned int to uint16_t for use in the professional Ender 3V2/S1 firmware + * Url: https://www.arduino.cc/reference/en/libraries/base64/ + */ + +#ifndef BASE64_H_INCLUDED +#define BASE64_H_INCLUDED + +/* binary_to_base64: + * Description: + * Converts a single byte from a binary value to the corresponding base64 character + * Parameters: + * v - Byte to convert + * Returns: + * ascii code of base64 character. If byte is >= 64, then there is not corresponding base64 character + * and 255 is returned + */ +unsigned char binary_to_base64(unsigned char v); + +/* base64_to_binary: + * Description: + * Converts a single byte from a base64 character to the corresponding binary value + * Parameters: + * c - Base64 character (as ascii code) + * Returns: + * 6-bit binary value + */ +unsigned char base64_to_binary(unsigned char c); + +/* encode_base64_length: + * Description: + * Calculates length of base64 string needed for a given number of binary bytes + * Parameters: + * input_length - Amount of binary data in bytes + * Returns: + * Number of base64 characters needed to encode input_length bytes of binary data + */ +uint16_t encode_base64_length(uint16_t input_length); + +/* decode_base64_length: + * Description: + * Calculates number of bytes of binary data in a base64 string + * Variant that does not use input_length no longer used within library, retained for API compatibility + * Parameters: + * input - Base64-encoded null-terminated string + * input_length (optional) - Number of bytes to read from input pointer + * Returns: + * Number of bytes of binary data in input + */ +uint16_t decode_base64_length(unsigned char input[]); +uint16_t decode_base64_length(unsigned char input[], uint16_t input_length); + +/* encode_base64: + * Description: + * Converts an array of bytes to a base64 null-terminated string + * Parameters: + * input - Pointer to input data + * input_length - Number of bytes to read from input pointer + * output - Pointer to output string. Null terminator will be added automatically + * Returns: + * Length of encoded string in bytes (not including null terminator) + */ +uint16_t encode_base64(unsigned char input[], uint16_t input_length, unsigned char output[]); + +/* decode_base64: + * Description: + * Converts a base64 null-terminated string to an array of bytes + * Parameters: + * input - Pointer to input string + * input_length (optional) - Number of bytes to read from input pointer + * output - Pointer to output array + * Returns: + * Number of bytes in the decoded binary + */ +uint16_t decode_base64(unsigned char input[], unsigned char output[]); +uint16_t decode_base64(unsigned char input[], uint16_t input_length, unsigned char output[]); + +unsigned char binary_to_base64(unsigned char v) { + // Capital letters - 'A' is ascii 65 and base64 0 + if (v < 26) return v + 'A'; + + // Lowercase letters - 'a' is ascii 97 and base64 26 + if (v < 52) return v + 71; + + // Digits - '0' is ascii 48 and base64 52 + if (v < 62) return v - 4; + + // '+' is ascii 43 and base64 62 + if (v == 62) return '+'; + + // '/' is ascii 47 and base64 63 + if (v == 63) return '/'; + + return 64; +} + +unsigned char base64_to_binary(unsigned char c) { + // Capital letters - 'A' is ascii 65 and base64 0 + if ('A' <= c && c <= 'Z') return c - 'A'; + + // Lowercase letters - 'a' is ascii 97 and base64 26 + if ('a' <= c && c <= 'z') return c - 71; + + // Digits - '0' is ascii 48 and base64 52 + if ('0' <= c && c <= '9') return c + 4; + + // '+' is ascii 43 and base64 62 + if (c == '+') return 62; + + // '/' is ascii 47 and base64 63 + if (c == '/') return 63; + + return 255; +} + +uint16_t encode_base64_length(uint16_t input_length) { + return (input_length + 2)/3*4; +} + +uint16_t decode_base64_length(unsigned char input[]) { + return decode_base64_length(input, -1); +} + +uint16_t decode_base64_length(unsigned char input[], uint16_t input_length) { + unsigned char *start = input; + + while (base64_to_binary(input[0]) < 64 && (unsigned char)(input - start) < input_length) { + ++input; + } + + input_length = input - start; + return input_length/4*3 + (input_length % 4 ? input_length % 4 - 1 : 0); +} + +uint16_t encode_base64(unsigned char input[], uint16_t input_length, unsigned char output[]) { + uint16_t full_sets = input_length/3; + + // While there are still full sets of 24 bits... + for (uint16_t i = 0; i < full_sets; ++i) { + output[0] = binary_to_base64( input[0] >> 2); + output[1] = binary_to_base64((input[0] & 0x03) << 4 | input[1] >> 4); + output[2] = binary_to_base64((input[1] & 0x0F) << 2 | input[2] >> 6); + output[3] = binary_to_base64( input[2] & 0x3F); + + input += 3; + output += 4; + } + + switch(input_length % 3) { + case 0: + output[0] = '\0'; + break; + case 1: + output[0] = binary_to_base64( input[0] >> 2); + output[1] = binary_to_base64((input[0] & 0x03) << 4); + output[2] = '='; + output[3] = '='; + output[4] = '\0'; + break; + case 2: + output[0] = binary_to_base64( input[0] >> 2); + output[1] = binary_to_base64((input[0] & 0x03) << 4 | input[1] >> 4); + output[2] = binary_to_base64((input[1] & 0x0F) << 2); + output[3] = '='; + output[4] = '\0'; + break; + } + + return encode_base64_length(input_length); +} + +uint16_t decode_base64(unsigned char input[], unsigned char output[]) { + return decode_base64(input, -1, output); +} + +uint16_t decode_base64(unsigned char input[], uint16_t input_length, unsigned char output[]) { + uint16_t output_length = decode_base64_length(input, input_length); + + // While there are still full sets of 24 bits... + for (uint16_t i = 2; i < output_length; i += 3) { + output[0] = base64_to_binary(input[0]) << 2 | base64_to_binary(input[1]) >> 4; + output[1] = base64_to_binary(input[1]) << 4 | base64_to_binary(input[2]) >> 2; + output[2] = base64_to_binary(input[2]) << 6 | base64_to_binary(input[3]); + + input += 4; + output += 3; + } + + switch(output_length % 3) { + case 1: + output[0] = base64_to_binary(input[0]) << 2 | base64_to_binary(input[1]) >> 4; + break; + case 2: + output[0] = base64_to_binary(input[0]) << 2 | base64_to_binary(input[1]) >> 4; + output[1] = base64_to_binary(input[1]) << 4 | base64_to_binary(input[2]) >> 2; + break; + } + + return output_length; +} + +#endif // ifndef diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 9db6355e98bd..07b134471b58 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -23,14 +23,45 @@ /** * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.15.2 - * Date: 2022/03/01 + * Version: 3.17.2 + * Date: 2022/04/08 */ #include "../../../inc/MarlinConfig.h" #if ENABLED(DWIN_LCD_PROUI) +#if DISABLED(LIMITED_MAX_FR_EDITING) + #warning "LIMITED_MAX_FR_EDITING is recommended with ProUI." +#endif +#if DISABLED(LIMITED_MAX_ACCEL_EDITING) + #warning "LIMITED_MAX_ACCEL_EDITING is recommended with ProUI." +#endif +#if ENABLED(CLASSIC_JERK) && DISABLED(LIMITED_JERK_EDITING) + #warning "LIMITED_JERK_EDITING is recommended with ProUI." +#endif +#if DISABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) + #warning "INDIVIDUAL_AXIS_HOMING_SUBMENU is recommended with ProUI." +#endif +#if DISABLED(LCD_SET_PROGRESS_MANUALLY) + #warning "LCD_SET_PROGRESS_MANUALLY is recommended with ProUI." +#endif +#if DISABLED(STATUS_MESSAGE_SCROLLING) + #warning "STATUS_MESSAGE_SCROLLING is recommended with ProUI." +#endif +#if DISABLED(BAUD_RATE_GCODE) + #warning "BAUD_RATE_GCODE is recommended with ProUI." +#endif +#if DISABLED(SOUND_MENU_ITEM) + #warning "SOUND_MENU_ITEM is recommended with ProUI." +#endif +#if DISABLED(PRINTCOUNTER) + #warning "PRINTCOUNTER is recommended with ProUI." +#endif +#if HAS_MESH && DISABLED(MESH_EDIT_MENU) + #warning "MESH_EDIT_MENU is recommended with ProUI." +#endif + #include "dwin.h" #include "menus.h" #include "dwin_popup.h" @@ -64,7 +95,7 @@ #include "../../../feature/host_actions.h" #endif -#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) && DISABLED(PROBE_MANUALLY) +#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) #define HAS_ONESTEP_LEVELING 1 #endif @@ -82,11 +113,11 @@ #if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) #define HAS_ZOFFSET_ITEM 1 - #if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) - #define JUST_BABYSTEP 1 - #endif - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ENABLED(BABYSTEPPING) #include "../../../feature/babystep.h" + #if !HAS_BED_PROBE + #define JUST_BABYSTEP 1 + #endif #endif #endif @@ -94,18 +125,26 @@ #include "../../../feature/powerloss.h" #endif -#if HAS_GCODE_PREVIEW - #include "gcode_preview.h" -#endif - #if HAS_ESDIAG #include "endstop_diag.h" #endif +#if HAS_PIDPLOT + #include "plot.h" +#endif + +#if HAS_GCODE_PREVIEW + #include "gcode_preview.h" +#endif + #if HAS_MESH #include "meshviewer.h" #endif +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "ubl_tools.h" +#endif + #if ENABLED(PRINTCOUNTER) #include "printstats.h" #endif @@ -143,29 +182,31 @@ // Load and Unload limits #define MAX_LOAD_UNLOAD 500 -// Feedspeed limit (max feedspeed = DEFAULT_MAX_FEEDRATE * 2) +// Feedspeed limit (max feedspeed = MAX_FEEDRATE_EDIT_VALUES) #define MIN_MAXFEEDSPEED 1 #define MIN_MAXACCELERATION 1 #define MIN_MAXJERK 0.1 #define MIN_STEP 1 #define MAX_STEP 999.9 -// Extruder's temperature limits -#define MIN_ETEMP HEATER_0_MINTEMP -#define MAX_ETEMP (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT) +// Editable temperature limits +#define MIN_ETEMP 0 +#define MAX_ETEMP (HEATER_0_MAXTEMP - (HOTEND_OVERSHOOT)) +#define MIN_BEDTEMP 0 +#define MAX_BEDTEMP BED_MAX_TARGET #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) -#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) +#if HAS_MESH + #define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, HMI_data.ManualZOffset) +#else + float z_offset = 0; + #define BABY_Z_VAR z_offset +#endif // Structs HMI_value_t HMI_value; @@ -203,11 +244,28 @@ uint8_t index_file = MROWS; bool hash_changed = true; // Flag to know if message status was changed -constexpr float max_feedrate_edit_values[] = DEFAULT_MAX_FEEDRATE; -constexpr float max_acceleration_edit_values[] = DEFAULT_MAX_ACCELERATION; - +constexpr float max_feedrate_edit_values[] = + #ifdef MAX_FEEDRATE_EDIT_VALUES + MAX_FEEDRATE_EDIT_VALUES + #else + { 1000, 1000, 10, 50 } + #endif +; +constexpr float max_acceleration_edit_values[] = + #ifdef MAX_ACCEL_EDIT_VALUES + MAX_ACCEL_EDIT_VALUES + #else + { 1000, 1000, 200, 2000 } + #endif +; #if HAS_CLASSIC_JERK - constexpr float max_jerk_edit_values[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; + constexpr float max_jerk_edit_values[] = + #ifdef MAX_JERK_EDIT_VALUES + MAX_JERK_EDIT_VALUES + #else + { DEFAULT_XJERK * 2, DEFAULT_YJERK * 2, DEFAULT_ZJERK * 2, DEFAULT_EJERK * 2 } + #endif + ; #endif static uint8_t _percent_done = 0; @@ -216,10 +274,6 @@ static uint32_t _remain_time = 0; // Additional Aux Host Support static bool sdprint = false; -#if HAS_ZOFFSET_ITEM - float dwin_zoffset = 0, last_zoffset = 0; -#endif - #if HAS_HOTEND float last_E = 0; #endif @@ -267,12 +321,22 @@ MenuClass *BedPIDMenu = nullptr; #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) MenuClass *HomingMenu = nullptr; #endif +#if ENABLED(FWRETRACT) + MenuClass *FWRetractMenu = nullptr; +#endif +#if HAS_MESH + MenuClass *MeshMenu = nullptr; + #if ENABLED(MESH_EDIT_MENU) + MenuClass *EditMeshMenu = nullptr; + #endif +#endif // Updatable menuitems pointers MenuItemClass *HotendTargetItem = nullptr; MenuItemClass *BedTargetItem = nullptr; MenuItemClass *FanSpeedItem = nullptr; MenuItemClass *MMeshMoveZItem = nullptr; +MenuItemClass *EditZValueItem = nullptr; #define DWIN_LANGUAGE_EEPROM_ADDRESS 0x01 // Between 0x01 and 0x63 (EEPROM_OFFSET-1) // BL24CXX::check() uses 0x00 @@ -432,7 +496,7 @@ void Draw_Back_First(const bool is_sel=true) { //PopUps void Popup_window_PauseOrStop() { if (HMI_IsChinese()) { - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); Draw_Popup_Bkgd(); if (select_print.now == PRINT_PAUSE_RESUME) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); else if (select_print.now == PRINT_STOP) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); @@ -451,7 +515,7 @@ void Popup_window_PauseOrStop() { void Popup_Window_ETempTooLow() { if (HMI_IsChinese()) { HMI_SaveProcessID(WaitResponse); - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); Draw_Popup_Bkgd(); DWINUI::Draw_Icon(ICON_TempTooLow, 102, 105); DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); @@ -469,7 +533,7 @@ void Popup_window_PauseOrStop() { void DWIN_Popup_Temperature(const bool toohigh) { HMI_SaveProcessID(WaitResponse); if (HMI_IsChinese()) { - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); Draw_Popup_Bkgd(); if (toohigh) { DWINUI::Draw_Icon(ICON_TempTooHigh, 102, 165); @@ -493,6 +557,11 @@ void DWIN_DrawStatusLine(const char *text) { if (text) DWINUI::Draw_CenteredString(HMI_data.StatusTxt_Color, STATUS_Y + 2, text); } +void DWIN_DrawStatusLine(FSTR_P fstr) { + DWIN_Draw_Rectangle(1, HMI_data.StatusBg_Color, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); + if (fstr) DWINUI::Draw_CenteredString(HMI_data.StatusTxt_Color, STATUS_Y + 2, fstr); +} + // Clear & reset status line void DWIN_ResetStatusLine() { ui.status_message[0] = 0; @@ -579,13 +648,13 @@ void Draw_Print_ProgressBar() { void Draw_Print_ProgressElapsed() { char buf[10]; duration_t elapsed = print_job_timer.duration(); // print timer - sprintf_P(buf, PSTR("%02i:%02i"), (uint16_t)(elapsed.value / 3600), ((uint16_t)elapsed.value % 3600) / 60); + sprintf_P(buf, PSTR("%02i:%02i "), (uint16_t)(elapsed.value / 3600), ((uint16_t)elapsed.value % 3600) / 60); DWINUI::Draw_String(HMI_data.Text_Color, HMI_data.Background_Color, 47, 192, buf); } void Draw_Print_ProgressRemain() { char buf[10]; - sprintf_P(buf, PSTR("%02i:%02i"), (uint16_t)(_remain_time / 3600), ((uint16_t)_remain_time % 3600) / 60); + sprintf_P(buf, PSTR("%02i:%02i "), (uint16_t)(_remain_time / 3600), ((uint16_t)_remain_time % 3600) / 60); DWINUI::Draw_String(HMI_data.Text_Color, HMI_data.Background_Color, 181, 192, buf); } @@ -612,7 +681,7 @@ void Draw_PrintProcess() { Title.FrameCopy(30, 1, 42, 14); // "Printing" else Title.ShowCaption(GET_TEXT_F(MSG_PRINTING)); - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); DWIN_Print_Header(sdprint ? card.longest_filename() : nullptr); Draw_Print_Labels(); DWINUI::Draw_Icon(ICON_PrintTime, 15, 173); @@ -631,6 +700,7 @@ void Goto_PrintProcess() { else { checkkey = PrintProcess; Draw_PrintProcess(); + TERN_(DASH_REDRAW, DWIN_RedrawDash()); } DWIN_UpdateLCD(); } @@ -641,16 +711,21 @@ void Draw_PrintDone() { _remain_time = 0; Title.ShowCaption(GET_TEXT_F(MSG_PRINT_DONE)); - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); DWIN_Print_Header(nullptr); - Draw_Print_ProgressBar(); - Draw_Print_Labels(); - DWINUI::Draw_Icon(ICON_PrintTime, 15, 173); - DWINUI::Draw_Icon(ICON_RemainTime, 150, 171); - Draw_Print_ProgressElapsed(); - Draw_Print_ProgressRemain(); - // show print done confirm - DWINUI::Draw_Button(BTN_Confirm, 86, 273); + if (sdprint && TERN0(HAS_GCODE_PREVIEW, Preview_Valid())) { + DWIN_ICON_Show(0, 0, 1, 21, 100, 0x00); + DWINUI::Draw_Button(BTN_Continue, 86, 300); + } + else { + Draw_Print_ProgressBar(); + Draw_Print_Labels(); + DWINUI::Draw_Icon(ICON_PrintTime, 15, 173); + DWINUI::Draw_Icon(ICON_RemainTime, 150, 171); + Draw_Print_ProgressElapsed(); + Draw_Print_ProgressRemain(); + DWINUI::Draw_Button(BTN_Continue, 86, 273); + } } void Goto_PrintDone() { @@ -663,7 +738,7 @@ void Goto_PrintDone() { } void Draw_Main_Menu() { - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); if (HMI_IsChinese()) Title.FrameCopy(2, 2, 26, 13); // "Home" etc else @@ -746,16 +821,13 @@ void update_variable() { if (checkkey == Menu && (CurrentMenu == TuneMenu || CurrentMenu == TemperatureMenu)) { // Tune page temperature update #if HAS_HOTEND - if (_new_hotend_target) - HotendTargetItem->draw(CurrentMenu->line(HotendTargetItem->pos)); + if (_new_hotend_target) HotendTargetItem->redraw(); #endif #if HAS_HEATED_BED - if (_new_bed_target) - BedTargetItem->draw(CurrentMenu->line(BedTargetItem->pos)); + if (_new_bed_target) BedTargetItem->redraw(); #endif #if HAS_FAN - if (_new_fanspeed) - FanSpeedItem->draw(CurrentMenu->line(FanSpeedItem->pos)); + if (_new_fanspeed) FanSpeedItem->redraw(); #endif } @@ -810,6 +882,8 @@ void update_variable() { else DWINUI::Draw_Icon(ICON_Zoffset, 187, 416); } + #else + DWINUI::Draw_Icon(ICON_Zoffset, 187, 416); #endif _draw_xyz_position(false); @@ -933,7 +1007,7 @@ void Redraw_SD_List() { select_file.reset(); index_file = MROWS; - DWINUI::ClearMenuArea(); // Leave title bar unchanged + DWINUI::ClearMainArea(); // Leave title bar unchanged Draw_Back_First(); @@ -1013,7 +1087,7 @@ void DWIN_Draw_Dashboard() { DWINUI::Draw_Icon(ICON_BedTemp, 10, 416); DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 28, 417, thermalManager.wholeDegBed()); DWINUI::Draw_String(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); - DWINUI::Draw_Int(true, true, 0, DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.degTargetBed()); + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.degTargetBed()); #endif DWINUI::Draw_Icon(ICON_Speed, 113, 383); @@ -1025,7 +1099,7 @@ void DWIN_Draw_Dashboard() { DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 195 + 2 * STAT_CHR_W, 384, thermalManager.fan_speed[0]); #endif - #if HAS_ZOFFSET_ITEM + #if BOTH(BABYSTEPPING, HAS_BED_PROBE) DWINUI::Draw_Icon(planner.leveling_active ? ICON_SetZOffset : ICON_Zoffset, 187, 416); #endif @@ -1041,7 +1115,7 @@ void DWIN_Draw_Dashboard() { } void Draw_Info_Menu() { - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); Draw_Back_First(); if (HMI_IsChinese()) Title.FrameCopy(30, 17, 28, 13); // "Info" @@ -1075,6 +1149,7 @@ void Draw_Print_File_Menu() { else Title.ShowCaption(GET_TEXT_F(MSG_MEDIA_MENU)); Redraw_SD_List(); + TERN_(DASH_REDRAW, DWIN_RedrawDash()); } // Main Process @@ -1107,7 +1182,7 @@ void HMI_MainMenu() { case PAGE_PRINT: checkkey = SelectFile; card.mount(); - delay(300); + safe_delay(300); Draw_Print_File_Menu(); break; case PAGE_PREPARE: Draw_Prepare_Menu(); break; @@ -1285,8 +1360,6 @@ void HMI_Printing() { #include "../../../libs/buzzer.h" -void HMI_AudioFeedback(const bool success/*=true*/) { DONE_BUZZ(success); } - void Draw_Main_Area() { switch (checkkey) { case MainMenu: Draw_Main_Menu(); break; @@ -1303,7 +1376,7 @@ void Draw_Main_Area() { case SetPInt: case SetIntNoDraw: case SetFloat: - case SetPFloat: CurrentMenu->draw(); break; + case SetPFloat: ReDrawMenu(); break; default: break; } } @@ -1322,15 +1395,8 @@ void HMI_WaitForUser() { select_page.reset(); Goto_Main_Menu(); break; - #if HAS_ONESTEP_LEVELING - case Leveling: - //TERN_(ProUI, ProEx.StopLeveling()); - HMI_ReturnScreen(); - break; - #endif - default: - HMI_ReturnScreen(); - break; + TERN_(HAS_ONESTEP_LEVELING, case Leveling:) + default: HMI_ReturnScreen(); break; } } } @@ -1349,22 +1415,25 @@ void HMI_Init() { void EachMomentUpdate() { static millis_t next_var_update_ms = 0, next_rts_update_ms = 0, next_status_update_ms = 0; - const millis_t ms = millis(); + if (ELAPSED(ms, next_var_update_ms)) { next_var_update_ms = ms + DWIN_VAR_UPDATE_INTERVAL; update_variable(); - switch (checkkey) { - #if HAS_ESDIAG - case ESDiagProcess: - ESDiag.Update(); - break; - #endif - default: - break; - } + #if HAS_ESDIAG + if (checkkey == ESDiagProcess) ESDiag.Update(); + #endif + #if HAS_PIDPLOT + if (checkkey == PidProcess) Plot.Update((HMI_value.pidresult == PID_EXTR_START) ? thermalManager.wholeDegHotend(0) : thermalManager.wholeDegBed()); + #endif } + #if HAS_STATUS_MESSAGE_TIMEOUT + bool did_expire = ui.status_reset_callback && (*ui.status_reset_callback)(); + did_expire |= ui.status_message_expire_ms && ELAPSED(ms, ui.status_message_expire_ms); + if (did_expire) ui.reset_status(); + #endif + if (ELAPSED(ms, next_status_update_ms)) { next_status_update_ms = ms + 500; DWIN_DrawStatusMessage(); @@ -1402,7 +1471,7 @@ void EachMomentUpdate() { duration_t elapsed = print_job_timer.duration(); // print timer - if (sdprint && card.isPrinting()) { + if (sdprint && card.isPrinting() && !HMI_flag.percent_flag) { uint8_t percentDone = card.percentDone(); if (_percent_done != percentDone) { // print percent _percent_done = percentDone; @@ -1439,7 +1508,7 @@ void EachMomentUpdate() { #if ENABLED(POWER_LOSS_RECOVERY) void Popup_PowerLossRecovery() { - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); Draw_Popup_Bkgd(); if (HMI_IsChinese()) { DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 115); @@ -1478,7 +1547,7 @@ void EachMomentUpdate() { void Goto_PowerLossRecovery() { recovery.dwin_flag = false; - LCD_MESSAGE_F(GET_TEXT_F(MSG_CONTINUE_PRINT_JOB)); + LCD_MESSAGE(MSG_CONTINUE_PRINT_JOB); Goto_Popup(Popup_PowerLossRecovery, onClick_PowerLossRecovery); } @@ -1497,8 +1566,7 @@ void DWIN_HandleScreen() { case SelectFile: HMI_SelectFile(); break; case PrintProcess: HMI_Printing(); break; case Popup: HMI_Popup(); break; - case Leveling: //TERN_(ProUI, HMI_WaitForUser()); - break; + case Leveling: break; case Locked: HMI_LockScreen(); break; case PrintDone: TERN_(HAS_ESDIAG, case ESDiagProcess:) @@ -1541,7 +1609,10 @@ void DWIN_HomingStart() { void DWIN_HomingDone() { HMI_flag.home_flag = false; - dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); + #if ENABLED(MESH_BED_LEVELING) && EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + planner.synchronize(); + babystep.add_mm(Z_AXIS, HMI_data.ManualZOffset); + #endif if (HMI_flag.abort_action) DWIN_Print_Aborted(); else HMI_ReturnScreen(); } @@ -1550,13 +1621,25 @@ void DWIN_LevelingStart() { HMI_SaveProcessID(Leveling); Title.ShowCaption(GET_TEXT_F(MSG_BED_LEVELING)); DWIN_Show_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), GET_TEXT_F(MSG_PLEASE_WAIT)); + #if BOTH(AUTO_BED_LEVELING_UBL, PREHEAT_BEFORE_LEVELING) + #if HAS_HOTEND + if (thermalManager.degTargetHotend(0) < LEVELING_NOZZLE_TEMP) + thermalManager.setTargetHotend(LEVELING_NOZZLE_TEMP, 0); + #endif + #if HAS_HEATED_BED + if (thermalManager.degTargetBed() < HMI_data.BedLevT) + thermalManager.setTargetBed(HMI_data.BedLevT); + #endif + TERN_(HAS_HOTEND, thermalManager.wait_for_hotend(0)); + TERN_(HAS_HEATED_BED, thermalManager.wait_for_bed_heating()); + #endif #elif ENABLED(MESH_BED_LEVELING) Draw_ManualMesh_Menu(); #endif } void DWIN_LevelingDone() { - TERN_(HAS_ONESTEP_LEVELING, if (planner.leveling_active) Goto_MeshViewer()); + TERN_(HAS_MESH, Goto_MeshViewer()); } #if HAS_MESH @@ -1569,27 +1652,61 @@ void DWIN_LevelingDone() { #endif // PID process + +#if HAS_PIDPLOT + void DWIN_Draw_PIDPopup() { + frame_rect_t gfrm = {40, 180, DWIN_WIDTH - 80, 120}; + DWINUI::ClearMainArea(); + Draw_Popup_Bkgd(); + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 100, GET_TEXT_F(MSG_PID_AUTOTUNE)); + DWINUI::Draw_String(HMI_data.PopupTxt_Color, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("PID target: Celsius")); + switch (HMI_value.pidresult) { + case PID_EXTR_START: + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 120, F("for Nozzle is running.")); + Plot.Draw(gfrm, thermalManager.hotend_maxtemp[0], HMI_data.HotendPidT); + DWINUI::Draw_Int(HMI_data.PopupTxt_Color, 3, gfrm.x + 90, gfrm.y - DWINUI::fontHeight() - 4, HMI_data.HotendPidT); + break; + case PID_BED_START: + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 120, F("for BED is running.")); + Plot.Draw(gfrm, BED_MAXTEMP, HMI_data.BedPidT); + DWINUI::Draw_Int(HMI_data.PopupTxt_Color, 3, gfrm.x + 90, gfrm.y - DWINUI::fontHeight() - 4, HMI_data.BedPidT); + break; + default: + break; + } + } +#endif + void DWIN_PidTuning(pidresult_t result) { + HMI_value.pidresult = result; switch (result) { case PID_BED_START: - HMI_SaveProcessID(NothingToDo); - DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), F("for BED is running.")); + HMI_SaveProcessID(PidProcess); + #if HAS_PIDPLOT + DWIN_Draw_PIDPopup(); + #else + DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), F("for BED is running.")); + #endif break; case PID_EXTR_START: - HMI_SaveProcessID(NothingToDo); - DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), F("for Nozzle is running.")); + HMI_SaveProcessID(PidProcess); + #if HAS_PIDPLOT + DWIN_Draw_PIDPopup(); + #else + DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), F("for Nozzle is running.")); + #endif break; case PID_BAD_EXTRUDER_NUM: checkkey = last_checkkey; - DWIN_Popup_Confirm(ICON_TempTooLow, F("PID Autotune failed!"), F("Bad extruder")); + DWIN_Popup_Confirm(ICON_TempTooLow, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_BAD_EXTRUDER_NUM)); break; case PID_TUNING_TIMEOUT: checkkey = last_checkkey; - DWIN_Popup_Confirm(ICON_TempTooHigh, F("Error"), GET_TEXT_F(MSG_PID_TIMEOUT)); + DWIN_Popup_Confirm(ICON_TempTooHigh, GET_TEXT_F(MSG_ERROR), GET_TEXT_F(MSG_PID_TIMEOUT)); break; case PID_TEMP_TOO_HIGH: checkkey = last_checkkey; - DWIN_Popup_Confirm(ICON_TempTooHigh, F("PID Autotune failed!"), F("Temperature too high")); + DWIN_Popup_Confirm(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_TEMP_TOO_HIGH)); break; case PID_DONE: checkkey = last_checkkey; @@ -1606,6 +1723,7 @@ void DWIN_Print_Started(const bool sd) { sdprint = IS_SD_PRINTING() || sd; _percent_done = 0; _remain_time = 0; + HMI_flag.percent_flag = false; HMI_flag.remain_flag = false; HMI_flag.pause_flag = false; HMI_flag.pause_action = false; @@ -1637,7 +1755,7 @@ void DWIN_Print_Finished() { HMI_flag.pause_flag = false; wait_for_heatup = false; planner.finish_and_disable(); - thermalManager.cooldown(); + thermalManager.cooldown(); Goto_PrintDone(); } @@ -1652,10 +1770,13 @@ void DWIN_Print_Aborted() { } // Progress Bar update -void DWIN_Progress_Update() { - if (parser.seenval('P')) _percent_done = parser.byteval('P'); +void DWIN_M73() { + if (parser.seenval('P')) { + _percent_done = parser.value_byte(); + HMI_flag.percent_flag = true; + } if (parser.seenval('R')) { - _remain_time = parser.ulongval('R') * 60; + _remain_time = parser.value_ulong() * 60; HMI_flag.remain_flag = true; } if (checkkey == PrintProcess) { @@ -1705,16 +1826,18 @@ void DWIN_SetDataDefaults() { HMI_data.BedLevT = LEVELING_BED_TEMP; #endif TERN_(BAUD_RATE_GCODE, SetBaud250K()); + #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + leds.set_default(); + ApplyLEDColor(); + #endif } -void DWIN_StoreSettings(char *buff) { - memcpy(buff, &HMI_data, _MIN(sizeof(HMI_data), eeprom_data_size)); +void DWIN_CopySettingsTo(char * const buff) { + memcpy(buff, &HMI_data, eeprom_data_size); } -void DWIN_LoadSettings(const char *buff) { - // (void *)-> Avoid Warning when save data different from uintX_t in HMI_data_t struct - memcpy((void *)&HMI_data, buff, _MIN(sizeof(HMI_data), eeprom_data_size)); - dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); +void DWIN_CopySettingsFrom(const char * const buff) { + memcpy(&HMI_data, buff, sizeof(HMI_data_t)); if (HMI_data.Text_Color == HMI_data.Background_Color) DWIN_SetColorDefaults(); DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color, HMI_data.StatusBg_Color); TERN_(PREVENT_COLD_EXTRUSION, ApplyExtMinT()); @@ -1726,9 +1849,15 @@ void DWIN_LoadSettings(const char *buff) { caselight.update_brightness(); #endif #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) - // Apply Led Color - leds.set_color(HMI_data.Led_Color); + leds.set_color( + (HMI_data.LED_Color >> 16) & 0xFF, + (HMI_data.LED_Color >> 8) & 0xFF, + (HMI_data.LED_Color >> 0) & 0xFF + OPTARG(HAS_WHITE_LED, (HMI_data.LED_Color >> 24) & 0xFF) + ); + leds.update(); #endif + } // Initialize or re-initialize the LCD @@ -1741,11 +1870,17 @@ void MarlinUI::init_lcd() { void DWIN_InitScreen() { HMI_Init(); // draws boot screen - DWINUI::onCursorDraw = Draw_Menu_Cursor; - DWINUI::onCursorErase = Erase_Menu_Cursor; + onCursorDraw = Draw_Menu_Cursor; + onCursorErase = Erase_Menu_Cursor; DWINUI::onTitleDraw = Draw_Title; - DWINUI::onMenuDraw = Draw_Menu; - DWIN_DrawStatusLine(nullptr); + onMenuDraw = Draw_Menu; + checkkey = 255; + CurrentMenu = nullptr; + PreviousMenu = nullptr; + index_file = MROWS; + hash_changed = true; + last_E = 0; + DWIN_DrawStatusLine(FSTR_P(nullptr)); DWIN_Draw_Dashboard(); Goto_Main_Menu(); } @@ -1763,8 +1898,8 @@ void MarlinUI::refresh() { /* Nothing to see here */ } #endif void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component) { - DWIN_Draw_Popup(ICON_BLTouch, F("Printer killed:"), lcd_error); - DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 270, F("Turn off the printer")); + DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_PRINTER_KILLED), lcd_error); + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 270, GET_TEXT_F(MSG_TURN_OFF)); DWIN_UpdateLCD(); } @@ -1773,16 +1908,20 @@ void DWIN_RebootScreen() { DWIN_JPG_ShowAndCache(0); DWINUI::Draw_CenteredString(Color_White, 220, GET_TEXT_F(MSG_PLEASE_WAIT_REBOOT)); DWIN_UpdateLCD(); - delay(500); + safe_delay(500); } -void DWIN_Redraw_screen() { - Draw_Main_Area(); +void DWIN_RedrawDash() { hash_changed = true; DWIN_DrawStatusMessage(); DWIN_Draw_Dashboard(); } +void DWIN_RedrawScreen() { + Draw_Main_Area(); + DWIN_RedrawDash(); +} + #if ENABLED(ADVANCED_PAUSE_FEATURE) void DWIN_Popup_Pause(FSTR_P const fmsg, uint8_t button /*= 0*/) { HMI_SaveProcessID(button ? WaitResponse : NothingToDo); @@ -1809,15 +1948,15 @@ void DWIN_Redraw_screen() { case PAUSE_MESSAGE_OPTION: Goto_FilamentPurge(); break; case PAUSE_MESSAGE_RESUME: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_RESUME)); break; case PAUSE_MESSAGE_HEAT: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT), BTN_Continue); break; - case PAUSE_MESSAGE_HEATING: LCD_MESSAGE(MSG_FILAMENT_CHANGE_HEATING); break; + case PAUSE_MESSAGE_HEATING: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEATING)); break; case PAUSE_MESSAGE_STATUS: HMI_ReturnScreen(); break; // Exit from Pause, Load and Unload default: break; } } void Draw_Popup_FilamentPurge() { - DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), F("Purge or Continue?")); - DWINUI::Draw_Button(BTN_Confirm, 26, 280); + DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE_CONTINUE)); + DWINUI::Draw_Button(BTN_Purge, 26, 280); DWINUI::Draw_Button(BTN_Continue, 146, 280); Draw_Select_Highlight(true); } @@ -1872,10 +2011,30 @@ void HMI_LockScreen() { } -void Goto_ConfirmToPrint() { - card.openAndPrintFile(card.filename); - DWIN_Print_Started(true); -} +#if HAS_GCODE_PREVIEW + + void onClick_ConfirmToPrint() { + if (HMI_flag.select_flag) { // Confirm + card.openAndPrintFile(card.filename); + return DWIN_Print_Started(true); + } + else { // Cancel + DWIN_ResetStatusLine(); + checkkey = SelectFile; + return Draw_Print_File_Menu(); + } + } + + void Goto_ConfirmToPrint() { + Goto_Popup(Preview_DrawFromSD, onClick_ConfirmToPrint); + } + +#else + void Goto_ConfirmToPrint() { + card.openAndPrintFile(card.filename); + DWIN_Print_Started(true); + } +#endif #if HAS_ESDIAG void Draw_EndStopDiag() { @@ -1892,21 +2051,26 @@ void Goto_ConfirmToPrint() { #if ENABLED(EEPROM_SETTINGS) void WriteEeprom() { - const bool success = settings.save(); - HMI_AudioFeedback(success); + DWIN_DrawStatusLine(GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_UpdateLCD(); + DONE_BUZZ(settings.save()); } void ReadEeprom() { const bool success = settings.load(); - DWIN_Redraw_screen(); - HMI_AudioFeedback(success); + DWIN_RedrawScreen(); + DONE_BUZZ(success); } void ResetEeprom() { settings.reset(); - DWIN_Redraw_screen(); - HMI_AudioFeedback(); + DWIN_RedrawScreen(); + DONE_BUZZ(true); } + + #if HAS_MESH + void SaveMesh() { TERN(AUTO_BED_LEVELING_UBL, UBLSaveMesh(), WriteEeprom()); } + #endif #endif // Reset Printer @@ -1918,22 +2082,24 @@ void RebootPrinter() { hal.reboot(); } -void Goto_Info_Menu(){ +void Goto_Info_Menu() { Draw_Info_Menu(); + DWIN_UpdateLCD(); HMI_SaveProcessID(WaitResponse); } void Goto_Move_Menu() { #if HAS_HOTEND gcode.process_subcommands_now(F("G92E0")); // reset extruder position - planner.synchronize(); #endif Draw_Move_Menu(); } void DisableMotors() { queue.inject(F("M84")); } -void AutoLev() { queue.inject(F("G28XYO\nG28Z\nG29")); } // Force to get the current Z home position +void AutoLev() { // Always reacquire the Z "home" position + queue.inject(F(TERN(AUTO_BED_LEVELING_UBL, "G28Z\nG29P1", "G28XYO\nG28Z\nG29"))); +} void AutoHome() { queue.inject_P(G28_STR); } void HomeX() { queue.inject(F("G28X")); } @@ -1942,49 +2108,57 @@ void HomeZ() { queue.inject(F("G28Z")); } void SetHome() { // Apply workspace offset, making the current position 0,0,0 - queue.inject(F("G92 X0 Y0 Z0")); - HMI_AudioFeedback(); + queue.inject(F("G92X0Y0Z0")); + DONE_BUZZ(true); } #if HAS_ZOFFSET_ITEM - bool printer_busy() { return planner.movesplanned() || printingIsActive(); } + void ApplyZOffset() { TERN_(EEPROM_SETTINGS, settings.save()); } void LiveZOffset() { - last_zoffset = dwin_zoffset; - dwin_zoffset = MenuData.Value / 100.0f; #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) - if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); + const_float_t step_zoffset = round((MenuData.Value / 100.0f) * planner.settings.axis_steps_per_mm[Z_AXIS]) - babystep.accum; + if (BABYSTEP_ALLOWED()) babystep.add_steps(Z_AXIS, step_zoffset); #endif } - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + + #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) void SetZOffset() { + babystep.accum = round(planner.settings.axis_steps_per_mm[Z_AXIS] * BABY_Z_VAR); SetPFloatOnClick(Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, 2, ApplyZOffset, LiveZOffset); } #endif void SetMoveZto0() { - char cmd[48] = ""; - char str_1[5] = "", str_2[5] = ""; - sprintf_P(cmd, PSTR("G28XYO\nG28Z\nG0X%sY%sF5000\nM420S0\nG0Z0F300"), - #if ENABLED(MESH_BED_LEVELING) - dtostrf(0, 1, 1, str_1), - dtostrf(0, 1, 1, str_2) - #else - dtostrf(X_CENTER, 1, 1, str_1), - dtostrf(Y_CENTER, 1, 1, str_2) - #endif - ); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - LCD_MESSAGE_F("Now adjust Z Offset"); - HMI_AudioFeedback(true); + #if ENABLED(Z_SAFE_HOMING) + char cmd[54], str_1[5], str_2[5]; + sprintf_P(cmd, PSTR("G28XYO\nG28Z\nG0X%sY%sF5000\nM420S0\nG0Z0F300\nM400"), + dtostrf(Z_SAFE_HOMING_X_POINT, 1, 1, str_1), + dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 1, str_2) + ); + gcode.process_subcommands_now(cmd); + #else + gcode.process_subcommands_now(F("G28O\nM420S0\nG0Z0F300\nM400")); + #endif + ui.reset_status(); + DONE_BUZZ(true); + } + + void HomeZandDisable() { + SetMoveZto0(); + DisableMotors(); } -#endif + +#endif // HAS_ZOFFSET_ITEM #if HAS_PREHEAT void DoPreheat0() { ui.preheat_all(0); } - void DoPreheat1() { ui.preheat_all(1); } - void DoPreheat2() { ui.preheat_all(2); } + #if PREHEAT_COUNT >= 2 + void DoPreheat1() { ui.preheat_all(1); } + #if PREHEAT_COUNT >= 3 + void DoPreheat2() { ui.preheat_all(2); } + #endif + #endif #endif void DoCoolDown() { thermalManager.cooldown(); } @@ -2009,9 +2183,9 @@ void ApplyMoveE() { planner.buffer_line(current_position, MMM_TO_MMS(FEEDRATE_E)); } } -void SetMoveX() { HMI_value.axis = X_AXIS; SetPFloatOnClick(X_MIN_POS, X_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove);} -void SetMoveY() { HMI_value.axis = Y_AXIS; SetPFloatOnClick(Y_MIN_POS, Y_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove);} -void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove);} +void SetMoveX() { HMI_value.axis = X_AXIS; SetPFloatOnClick(X_MIN_POS, X_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove); } +void SetMoveY() { HMI_value.axis = Y_AXIS; SetPFloatOnClick(Y_MIN_POS, Y_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove); } +void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove); } #if HAS_HOTEND void SetMoveE() { @@ -2024,14 +2198,13 @@ void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS #endif void SetPID(celsius_t t, heater_id_t h) { - char cmd[48] = ""; + char cmd[53] = ""; char str_1[5] = "", str_2[5] = ""; - sprintf_P(cmd, PSTR("G28OXY\nG0Z5F300\nG0X%sY%sF5000\nM84"), + sprintf_P(cmd, PSTR("G28OXY\nG0Z5F300\nG0X%sY%sF5000\nM84\nM400"), dtostrf(X_CENTER, 1, 1, str_1), dtostrf(Y_CENTER, 1, 1, str_2) ); gcode.process_subcommands_now(cmd); - planner.synchronize(); thermalManager.PID_autotune(t, h, HMI_data.PidCycles, true); } #if HAS_HOTEND @@ -2066,7 +2239,7 @@ void SetPID(celsius_t t, heater_id_t h) { void ApplyBrightness() { ui.set_brightness(MenuData.Value); } void LiveBrightness() { DWIN_LCD_Brightness(MenuData.Value); } void SetBrightness() { SetIntOnClick(LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, ui.brightness, ApplyBrightness, LiveBrightness); } - void TurnOffBacklight() { HMI_SaveProcessID(WaitResponse); ui.set_brightness(0); DWIN_Redraw_screen(); } + void TurnOffBacklight() { HMI_SaveProcessID(WaitResponse); ui.set_brightness(0); DWIN_RedrawScreen(); } #endif #if ENABLED(CASE_LIGHT_MENU) @@ -2077,7 +2250,7 @@ void SetPID(celsius_t t, heater_id_t h) { DWIN_UpdateLCD(); } #if ENABLED(CASELIGHT_USES_BRIGHTNESS) - void LiveCaseLightBrightness() { HMI_data.CaseLight_Brightness = caselight.brightness = MenuData.Value; caselight.update_brightness(); } + void LiveCaseLightBrightness() { caselight.brightness = MenuData.Value; caselight.update_brightness(); } void SetCaseLightBrightness() { SetIntOnClick(0, 255, caselight.brightness, nullptr, LiveCaseLightBrightness); } #endif #endif @@ -2090,24 +2263,26 @@ void SetPID(celsius_t t, heater_id_t h) { DWIN_UpdateLCD(); } #endif - #if ENABLED(HAS_COLOR_LEDS) - void LiveLedColorR() { leds.color.r = MenuData.Value; HMI_data.Led_Color = leds.color; leds.update(); } - void SetLedColorR() { SetIntOnClick(0, 255, leds.color.r, nullptr, LiveLedColorR); } - void LiveLedColorG() { leds.color.g = MenuData.Value; HMI_data.Led_Color = leds.color; leds.update(); } - void SetLedColorG() { SetIntOnClick(0, 255, leds.color.g, nullptr, LiveLedColorG); } - void LiveLedColorB() { leds.color.b = MenuData.Value; HMI_data.Led_Color = leds.color; leds.update(); } - void SetLedColorB() { SetIntOnClick(0, 255, leds.color.b, nullptr, LiveLedColorB); } + #if HAS_COLOR_LEDS + void ApplyLEDColor() { HMI_data.LED_Color = TERN0(HAS_WHITE_LED, (leds.color.w << 24)) | (leds.color.r << 16) | (leds.color.g << 8) | leds.color.b; } + void LiveLEDColor(uint8_t *color) { *color = MenuData.Value; leds.update(); } + void LiveLEDColorR() { LiveLEDColor(&leds.color.r); } + void LiveLEDColorG() { LiveLEDColor(&leds.color.g); } + void LiveLEDColorB() { LiveLEDColor(&leds.color.b); } + void SetLEDColorR() { SetIntOnClick(0, 255, leds.color.r, ApplyLEDColor, LiveLEDColorR); } + void SetLEDColorG() { SetIntOnClick(0, 255, leds.color.g, ApplyLEDColor, LiveLEDColorG); } + void SetLEDColorB() { SetIntOnClick(0, 255, leds.color.b, ApplyLEDColor, LiveLEDColorB); } #if HAS_WHITE_LED - void LiveLedColorW() { leds.color.w = MenuData.Value; HMI_data.Led_Color = leds.color; leds.update(); } - void SetLedColorW() { SetIntOnClick(0, 255, leds.color.w, nullptr, LiveLedColorW); } + void LiveLEDColorW() { LiveLEDColor(&leds.color.w); } + void SetLEDColorW() { SetIntOnClick(0, 255, leds.color.w, ApplyLEDColor, LiveLEDColorW); } #endif #endif #endif #if ENABLED(SOUND_MENU_ITEM) void SetEnableSound() { - ui.buzzer_enabled = !ui.buzzer_enabled; - Draw_Chkb_Line(CurrentMenu->line(), ui.buzzer_enabled); + ui.sound_on = !ui.sound_on; + Draw_Chkb_Line(CurrentMenu->line(), ui.sound_on); DWIN_UpdateLCD(); } #endif @@ -2138,10 +2313,6 @@ void SetPID(celsius_t t, heater_id_t h) { } #endif - #if BOTH(HAS_HEATED_BED, PREHEAT_BEFORE_LEVELING) - void SetBedLevT() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); } - #endif - #endif #if HAS_FILAMENT_SENSOR @@ -2170,7 +2341,7 @@ void SetPID(celsius_t t, heater_id_t h) { void RestoreDefaultsColors() { DWIN_SetColorDefaults(); DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color, HMI_data.StatusBg_Color); - DWIN_Redraw_screen(); + DWIN_RedrawScreen(); } void SelColor() { @@ -2196,7 +2367,7 @@ void DWIN_ApplyColor() { DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color, HMI_data.StatusBg_Color); Draw_SelectColors_Menu(); hash_changed = true; - LCD_MESSAGE_F(GET_TEXT_F(MSG_COLORS_APPLIED)); + LCD_MESSAGE(MSG_COLORS_APPLIED); DWIN_Draw_Dashboard(); } @@ -2209,7 +2380,7 @@ void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } #if HAS_HEATED_BED void ApplyBedTemp() { thermalManager.setTargetBed(MenuData.Value); } - void SetBedTemp() { SetIntOnClick(BED_MINTEMP, BED_MAX_TARGET, thermalManager.degTargetBed(), ApplyBedTemp); } + void SetBedTemp() { SetIntOnClick(MIN_BEDTEMP, MAX_BEDTEMP, thermalManager.degTargetBed(), ApplyBedTemp); } #endif #if HAS_FAN @@ -2224,18 +2395,18 @@ void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } queue.inject(F("M600 B2")); } - void ParkHead(){ + void ParkHead() { LCD_MESSAGE(MSG_FILAMENT_PARK_ENABLED); queue.inject(F("G28O\nG27")); } #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - void UnloadFilament(){ + void UnloadFilament() { LCD_MESSAGE(MSG_FILAMENTUNLOAD); queue.inject(F("M702 Z20")); } - void LoadFilament(){ + void LoadFilament() { LCD_MESSAGE(MSG_FILAMENTLOAD); queue.inject(F("M701 Z20")); } @@ -2247,48 +2418,45 @@ void ApplyFlow() { planner.refresh_e_factor(0); } void SetFlow() { SetPIntOnClick(MIN_PRINT_FLOW, MAX_PRINT_FLOW, ApplyFlow); } // Bed Tramming -TERN(HAS_ONESTEP_LEVELING, float, void) Tram(uint8_t point) { - char cmd[100] = ""; - #if HAS_ONESTEP_LEVELING - static bool inLev = false; - float xpos = 0, ypos = 0, zval = 0, margin = 0; - char str_1[6] = "", str_2[6] = "", str_3[6] = ""; - if (inLev) return NAN; - margin = HMI_data.FullManualTramming ? 30 : PROBING_MARGIN; - #else - int16_t xpos = 0, ypos = 0; - int16_t margin = 30; - #endif +void TramXY(const uint8_t point, const float &margin, float &x, float &y) { switch (point) { case 0: LCD_MESSAGE(MSG_LEVBED_FL); - xpos = ypos = margin; + x = y = margin; break; case 1: LCD_MESSAGE(MSG_LEVBED_FR); - xpos = X_BED_SIZE - margin; ypos = margin; + x = X_BED_SIZE - margin; y = margin; break; case 2: LCD_MESSAGE(MSG_LEVBED_BR); - xpos = X_BED_SIZE - margin; ypos = Y_BED_SIZE - margin; + x = X_BED_SIZE - margin; y = Y_BED_SIZE - margin; break; case 3: LCD_MESSAGE(MSG_LEVBED_BL); - xpos = margin; ypos = Y_BED_SIZE - margin; + x = margin; y = Y_BED_SIZE - margin; break; case 4: LCD_MESSAGE(MSG_LEVBED_C); - xpos = X_BED_SIZE / 2; ypos = Y_BED_SIZE / 2; + x = X_CENTER; y = Y_CENTER; break; } +} - planner.synchronize(); +#if HAS_BED_PROBE - #if HAS_ONESTEP_LEVELING + float Tram(const uint8_t point) { + char cmd[100] = ""; + static bool inLev = false; + float xpos = 0, ypos = 0, zval = 0, margin = 0; + char str_1[6] = "", str_2[6] = "", str_3[6] = ""; + if (inLev) return NAN; + margin = HMI_data.FullManualTramming ? 30 : PROBING_MARGIN; + + TramXY(point, margin, xpos, ypos); if (HMI_data.FullManualTramming) { - planner.synchronize(); sprintf_P(cmd, PSTR("M420S0\nG28O\nG90\nG0Z5F300\nG0X%sY%sF5000\nG0Z0F300"), dtostrf(xpos, 1, 1, str_1), dtostrf(ypos, 1, 1, str_2) @@ -2296,15 +2464,28 @@ TERN(HAS_ONESTEP_LEVELING, float, void) Tram(uint8_t point) { queue.inject(cmd); } else { - LIMIT(xpos, X_MIN_POS, (X_MAX_POS + probe.offset.x)); - LIMIT(ypos, Y_MIN_POS, (Y_MAX_POS + probe.offset.y)); + // AUTO_BED_LEVELING_BILINEAR does not define MESH_INSET + #ifndef MESH_MIN_X + #define MESH_MIN_X (_MAX(X_MIN_BED + PROBING_MARGIN, X_MIN_POS)) + #endif + #ifndef MESH_MIN_Y + #define MESH_MIN_Y (_MAX(Y_MIN_BED + PROBING_MARGIN, Y_MIN_POS)) + #endif + #ifndef MESH_MAX_X + #define MESH_MAX_X (_MIN(X_MAX_BED - (PROBING_MARGIN), X_MAX_POS)) + #endif + #ifndef MESH_MAX_Y + #define MESH_MAX_Y (_MIN(Y_MAX_BED - (PROBING_MARGIN), Y_MAX_POS)) + #endif + + LIMIT(xpos, MESH_MIN_X, MESH_MAX_X); + LIMIT(ypos, MESH_MIN_Y, MESH_MAX_Y); probe.stow(); gcode.process_subcommands_now(F("M420S0\nG28O")); - planner.synchronize(); inLev = true; zval = probe.probe_at_point(xpos, ypos, PROBE_PT_STOW); if (isnan(zval)) - LCD_MESSAGE_F("Position Not Reachable, check offsets"); + LCD_MESSAGE(MSG_ZPROBE_OUT); else { sprintf_P(cmd, PSTR("X:%s, Y:%s, Z:%s"), dtostrf(xpos, 1, 1, str_1), @@ -2316,14 +2497,20 @@ TERN(HAS_ONESTEP_LEVELING, float, void) Tram(uint8_t point) { inLev = false; } return zval; + } - #else +#else + + void Tram(const uint8_t point) { + float xpos = 0, ypos = 0, margin = 30; + TramXY(point, margin, xpos, ypos); - sprintf_P(cmd, PSTR("M420S0\nG28O\nG90\nG0Z5F300\nG0X%iY%iF5000\nG0Z0F300"), xpos, ypos); + char cmd[100] = "", str_1[6] = "", str_2[6] = ""; + sprintf_P(cmd, PSTR("M420S0\nG28O\nG90\nG0Z5F300\nG0X%sY%sF5000\nG0Z0F300"), dtostrf(xpos, 1, 1, str_1), dtostrf(ypos, 1, 1, str_2)); queue.inject(cmd); + } - #endif -} +#endif void TramFL() { Tram(0); } void TramFR() { Tram(1); } @@ -2331,7 +2518,7 @@ void TramBR() { Tram(2); } void TramBL() { Tram(3); } void TramC () { Tram(4); } -#if HAS_ONESTEP_LEVELING +#if HAS_BED_PROBE void Trammingwizard() { bed_mesh_t zval = {0}; @@ -2348,22 +2535,30 @@ void TramC () { Tram(4); } MeshViewer.DrawMesh(zval, 2, 2); zval[0][1] = Tram(3); MeshViewer.DrawMesh(zval, 2, 2); - char str_1[6] = "", str_2[6] = ""; - ui.status_printf(0, F("Limits minZ: %s, maxZ: %s"), - dtostrf(MeshViewer.min, 1, 2, str_1), - dtostrf(MeshViewer.max, 1, 2, str_2) - ); + + DWINUI::Draw_CenteredString(140, F("Calculating average")); + DWINUI::Draw_CenteredString(160, F("and relative heights")); + safe_delay(1000); + float avg = 0.0f; + LOOP_L_N(x, 2) LOOP_L_N(y, 2) avg += zval[x][y]; + avg /= 4.0f; + LOOP_L_N(x, 2) LOOP_L_N(y, 2) zval[x][y] -= avg; + MeshViewer.DrawMesh(zval, 2, 2); + ui.reset_status(); + if (ABS(MeshViewer.max - MeshViewer.min) < 0.05) { DWINUI::Draw_CenteredString(140,F("Corners leveled")); DWINUI::Draw_CenteredString(160,F("Tolerance achieved!")); } else { uint8_t p = 0; - float d, max = 0; + float max = 0; FSTR_P plabel; - LOOP_L_N(x,2) LOOP_L_N(y,2) { - d = ABS(zval[x][y] - MeshViewer.avg); + bool s = true; + LOOP_L_N(x, 2) LOOP_L_N(y, 2) { + const float d = ABS(zval[x][y]); if (max < d) { + s = (zval[x][y] >= 0); max = d; p = x + 2 * y; } @@ -2375,9 +2570,10 @@ void TramC () { Tram(4); } case 0b11 : plabel = GET_TEXT_F(MSG_LEVBED_BR); break; default : plabel = F(""); break; } - DWINUI::Draw_CenteredString(130, F("Corners not leveled")); - DWINUI::Draw_CenteredString(150, F("Knob adjustment required")); - DWINUI::Draw_CenteredString(Color_Green, 170, plabel); + DWINUI::Draw_CenteredString(120, F("Corners not leveled")); + DWINUI::Draw_CenteredString(140, F("Knob adjustment required")); + DWINUI::Draw_CenteredString(Color_Green, 160, s ? F("Lower") : F("Raise")); + DWINUI::Draw_CenteredString(Color_Green, 180, plabel); } DWINUI::Draw_Button(BTN_Continue, 86, 305); checkkey = Menu; @@ -2390,14 +2586,13 @@ void TramC () { Tram(4); } DWIN_UpdateLCD(); } -#endif // HAS_ONESTEP_LEVELING +#endif // HAS_BED_PROBE #if ENABLED(MESH_BED_LEVELING) - void ManualMeshStart(){ + void ManualMeshStart() { LCD_MESSAGE(MSG_UBL_BUILD_MESH_MENU); gcode.process_subcommands_now(F("G28XYO\nG28Z\nM211S0\nG29S1")); - planner.synchronize(); #ifdef MANUAL_PROBE_START_Z const uint8_t line = CurrentMenu->line(MMeshMoveZItem->pos); DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, 2, VALX - 2 * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), MANUAL_PROBE_START_Z); @@ -2411,15 +2606,14 @@ void TramC () { Tram(4); } planner.buffer_line(current_position, homing_feedrate(Z_AXIS)); } } - void SetMMeshMoveZ() { SetPFloatOnClick(-1, 1, 2, planner.synchronize, LiveMeshMoveZ);} + void SetMMeshMoveZ() { SetPFloatOnClick(-1, 1, 2, planner.synchronize, LiveMeshMoveZ); } - void ManualMeshContinue(){ + void ManualMeshContinue() { gcode.process_subcommands_now(F("G29S2")); - planner.synchronize(); - MMeshMoveZItem->draw(CurrentMenu->line(MMeshMoveZItem->pos)); + MMeshMoveZItem->redraw(); } - void ManualMeshSave(){ + void ManualMeshSave() { LCD_MESSAGE(MSG_UBL_STORAGE_MESH_MENU); queue.inject(F("M211S1\nM500")); } @@ -2431,7 +2625,7 @@ void TramC () { Tram(4); } void SetPreheatEndTemp() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP); } #endif #if HAS_HEATED_BED - void SetPreheatBedTemp() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); } + void SetPreheatBedTemp() { SetPIntOnClick(MIN_BEDTEMP, MAX_BEDTEMP); } #endif #if HAS_FAN void SetPreheatFanSpeed() { SetPIntOnClick(0, 255); } @@ -2472,7 +2666,7 @@ void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP void SetHotendPidT() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP); } #endif #if HAS_HEATED_BED - void SetBedPidT() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); } + void SetBedPidT() { SetPIntOnClick(MIN_BEDTEMP, MAX_BEDTEMP); } #endif #if HAS_HOTEND || HAS_HEATED_BED @@ -2499,10 +2693,12 @@ void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP #endif #if ENABLED(FWRETRACT) - void SetRetractLength() { SetPFloatOnClick( 0, 10, UNITFDIGITS); }; - void SetRetractSpeed() { SetPFloatOnClick( 1, 90, UNITFDIGITS); }; - void SetZRaise() { SetPFloatOnClick( 0, 2, 2); }; - void SetRecoverSpeed() { SetPFloatOnClick( 1, 90, UNITFDIGITS); }; + void Return_FWRetract_Menu() { (PreviousMenu == FilSetMenu) ? Draw_FilSet_Menu() : Draw_Tune_Menu(); } + void SetRetractLength() { SetPFloatOnClick( 0, 10, UNITFDIGITS); } + void SetRetractSpeed() { SetPFloatOnClick( 1, 90, UNITFDIGITS); } + void SetZRaise() { SetPFloatOnClick( 0, 2, 2); } + void SetRecoverSpeed() { SetPFloatOnClick( 1, 90, UNITFDIGITS); } + void SetAddRecover() { SetPFloatOnClick(-5, 5, UNITFDIGITS); } #endif // Special Menuitem Drawing functions ================================================= @@ -2582,7 +2778,7 @@ void onDrawAutoHome(MenuItemClass* menuitem, int8_t line) { } #if HAS_ZOFFSET_ITEM - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) void onDrawZOffset(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 174, 164, 223, 177); onDrawPFloat2Menu(menuitem, line); @@ -2600,10 +2796,12 @@ void onDrawAutoHome(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 100, 89, 151, 101); onDrawMenuItem(menuitem, line); } - void onDrawPreheat2(MenuItemClass* menuitem, int8_t line) { - if (HMI_IsChinese()) menuitem->SetFrame(1, 180, 89, 233, 100); - onDrawMenuItem(menuitem, line); - } + #if PREHEAT_COUNT > 1 + void onDrawPreheat2(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 180, 89, 233, 100); + onDrawMenuItem(menuitem, line); + } + #endif #endif #if HAS_PREHEAT @@ -2619,32 +2817,6 @@ void onDrawLanguage(MenuItemClass* menuitem, int8_t line) { DWINUI::Draw_String(VALX, MBASE(line), HMI_IsChinese() ? F("CN") : F("EN")); } -#if ENABLED(POWER_LOSS_RECOVERY) - void onDrawPwrLossR(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, recovery.enabled); } -#endif - -#if ENABLED(BAUD_RATE_GCODE) - void onDrawBaudrate(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, HMI_data.Baud115K); } -#endif - -#if ENABLED(CASE_LIGHT_MENU) - void onDrawCaseLight(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, caselight.on); } -#endif - -#if ENABLED(LED_CONTROL_MENU) - #if !BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) - void onDrawLedStatus(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, leds.lights_on); } - #endif -#endif - -#if ENABLED(SOUND_MENU_ITEM) - void onDrawEnableSound(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, ui.buzzer_enabled); } -#endif - -#ifdef BLTOUCH_HS_MODE - void onDrawHSMode(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, bltouch.high_speed_mode); } -#endif - void onDrawSelColorItem(MenuItemClass* menuitem, int8_t line) { const uint16_t color = *(uint16_t*)static_cast(menuitem)->value; DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, ICOX + 1, MBASE(line) - 1 + 1, ICOX + 18, MBASE(line) - 1 + 18); @@ -2736,10 +2908,12 @@ void onDrawSteps(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 100, 89, 178, 101); onDrawSubMenu(menuitem,line); } - void onDrawABSPreheatSubMenu(MenuItemClass* menuitem, int8_t line) { - if (HMI_IsChinese()) menuitem->SetFrame(1, 180, 89, 260, 100); - onDrawSubMenu(menuitem,line); - } + #if PREHEAT_COUNT >= 2 + void onDrawABSPreheatSubMenu(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 180, 89, 260, 100); + onDrawSubMenu(menuitem,line); + } + #endif #endif // HAS_PREHEAT void onDrawSpeed(MenuItemClass* menuitem, int8_t line) { @@ -2936,70 +3110,67 @@ void Draw_Prepare_Menu() { if (CurrentMenu != PrepareMenu) { CurrentMenu = PrepareMenu; SetMenuTitle({133, 1, 28, 13}, GET_TEXT_F(MSG_PREPARE)); - DWINUI::MenuItemsPrepare(13); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + MenuItemsPrepare(13); + BACK_ITEM(Goto_Main_Menu); #if ENABLED(ADVANCED_PAUSE_FEATURE) - MENU_ITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu); + MENU_ITEM_F(ICON_FilMan, MSG_FILAMENT_MAN, onDrawSubMenu, Draw_FilamentMan_Menu); #endif - MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_MOVE_AXIS), onDrawMoveSubMenu, Goto_Move_Menu); - MENU_ITEM(ICON_Tram, GET_TEXT_F(MSG_BED_TRAMMING), onDrawSubMenu, Draw_Tramming_Menu); - MENU_ITEM(ICON_CloseMotor, GET_TEXT_F(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); + MENU_ITEM_F(ICON_Axis, MSG_MOVE_AXIS, onDrawMoveSubMenu, Goto_Move_Menu); + MENU_ITEM_F(ICON_Tram, MSG_BED_TRAMMING, onDrawSubMenu, Draw_Tramming_Menu); + MENU_ITEM_F(ICON_CloseMotor, MSG_DISABLE_STEPPERS, onDrawDisableMotors, DisableMotors); #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) - MENU_ITEM(ICON_Homing, GET_TEXT_F(MSG_HOMING), onDrawSubMenu, Draw_Homing_Menu); + MENU_ITEM_F(ICON_Homing, MSG_HOMING, onDrawSubMenu, Draw_Homing_Menu); #else - MENU_ITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); + MENU_ITEM_F(ICON_Homing, MSG_AUTO_HOME, onDrawAutoHome, AutoHome); #endif #if ENABLED(MESH_BED_LEVELING) - MENU_ITEM(ICON_ManualMesh, GET_TEXT_F(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu); + MENU_ITEM_F(ICON_ManualMesh, MSG_MANUAL_MESH, onDrawSubMenu, Draw_ManualMesh_Menu); #endif #if HAS_ONESTEP_LEVELING - MENU_ITEM(ICON_Level, GET_TEXT_F(MSG_AUTO_MESH), onDrawMenuItem, AutoLev); + MENU_ITEM_F(ICON_Level, MSG_AUTO_MESH, onDrawMenuItem, AutoLev); #endif #if HAS_ZOFFSET_ITEM - #if HAS_BED_PROBE - MENU_ITEM(ICON_SetZOffset, GET_TEXT_F(MSG_PROBE_WIZARD), onDrawSubMenu, Draw_ZOffsetWiz_Menu); - #elif ENABLED(BABYSTEPPING) - EDIT_ITEM(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); + #if ENABLED(BABYSTEP_ZPROBE_OFFSET) + MENU_ITEM_F(ICON_SetZOffset, MSG_PROBE_WIZARD, onDrawSubMenu, Draw_ZOffsetWiz_Menu); + #elif JUST_BABYSTEP + EDIT_ITEM_F(ICON_Zoffset, MSG_ZPROBE_ZOFFSET, onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); #else - MENU_ITEM(ICON_SetHome, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); + MENU_ITEM_F(ICON_SetHome, MSG_SET_HOME_OFFSETS, onDrawHomeOffset, SetHome); #endif #endif #if HAS_PREHEAT - MENU_ITEM(ICON_PLAPreheat, GET_TEXT_F(MSG_PREHEAT_1), onDrawPreheat1, DoPreheat0); + MENU_ITEM_F(ICON_PLAPreheat, MSG_PREHEAT_1, onDrawPreheat1, DoPreheat0); #if PREHEAT_COUNT > 1 - MENU_ITEM(ICON_ABSPreheat, PSTR("Preheat " PREHEAT_2_LABEL), onDrawPreheat2, DoPreheat1); - #endif - #if PREHEAT_COUNT > 2 - MENU_ITEM(ICON_CustomPreheat, GET_TEXT_F(MSG_PREHEAT_CUSTOM), onDrawMenuItem, DoPreheat2); + MENU_ITEM(ICON_ABSPreheat, F("Preheat " PREHEAT_2_LABEL), onDrawPreheat2, DoPreheat1); + #if PREHEAT_COUNT > 2 + MENU_ITEM(ICON_CustomPreheat, F("Preheat " PREHEAT_3_LABEL), onDrawMenuItem, DoPreheat2); + #endif #endif #endif - MENU_ITEM(ICON_Cool, GET_TEXT_F(MSG_COOLDOWN), onDrawCooldown, DoCoolDown); - MENU_ITEM(ICON_Language, PSTR(GET_TEXT_F(MSG_UI_LANGUAGE)), onDrawLanguage, SetLanguage); + MENU_ITEM_F(ICON_Cool, MSG_COOLDOWN, onDrawCooldown, DoCoolDown); + MENU_ITEM_F(ICON_Language, MSG_UI_LANGUAGE, onDrawLanguage, SetLanguage); } ui.reset_status(true); CurrentMenu->draw(); } void Draw_Tramming_Menu() { - DWINUI::ClearMenuArea(); checkkey = Menu; - if (!TrammingMenu) TrammingMenu = new MenuClass(); - if (CurrentMenu != TrammingMenu) { - CurrentMenu = TrammingMenu; - SetMenuTitle({0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG - DWINUI::MenuItemsPrepare(8); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FL), onDrawMenuItem, TramFL); - MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FR), onDrawMenuItem, TramFR); - MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BR), onDrawMenuItem, TramBR); - MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BL), onDrawMenuItem, TramBL); - MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_C ), onDrawMenuItem, TramC ); - #if HAS_ONESTEP_LEVELING - MENU_ITEM(ICON_ProbeSet, F("Bed tramming wizard"), onDrawMenuItem, Trammingwizard); - MENU_ITEM(ICON_ProbeSet, GET_TEXT_F(MSG_BED_TRAMMING_MANUAL), onDrawManualTramming, SetManualTramming); + if (SetMenu(TrammingMenu, GET_TEXT_F(MSG_BED_TRAMMING), 8)) { + BACK_ITEM(Draw_Prepare_Menu); + #if HAS_BED_PROBE + MENU_ITEM_F(ICON_ProbeSet, MSG_TRAMMING_WIZARD, onDrawMenuItem, Trammingwizard); + EDIT_ITEM_F(ICON_ProbeSet, MSG_BED_TRAMMING_MANUAL, onDrawChkbMenu, SetManualTramming, &HMI_data.FullManualTramming); + #else + MENU_ITEM(ICON_MoveZ0, F("Home Z and disable"), onDrawMenuItem, HomeZandDisable); #endif + MENU_ITEM_F(ICON_Axis, MSG_LEVBED_FL, onDrawMenuItem, TramFL); + MENU_ITEM_F(ICON_Axis, MSG_LEVBED_FR, onDrawMenuItem, TramFR); + MENU_ITEM_F(ICON_Axis, MSG_LEVBED_BR, onDrawMenuItem, TramBR); + MENU_ITEM_F(ICON_Axis, MSG_LEVBED_BL, onDrawMenuItem, TramBL); + MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_C ), onDrawMenuItem, TramC ); } - CurrentMenu->draw(); + UpdateMenu(TrammingMenu); } void Draw_Control_Menu() { @@ -3008,27 +3179,27 @@ void Draw_Control_Menu() { if (CurrentMenu != ControlMenu) { CurrentMenu = ControlMenu; SetMenuTitle({103, 1, 28, 14}, GET_TEXT_F(MSG_CONTROL)); - DWINUI::MenuItemsPrepare(10); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + MenuItemsPrepare(10); + BACK_ITEM(Goto_Main_Menu); + MENU_ITEM_F(ICON_Temperature, MSG_TEMPERATURE, onDrawTempSubMenu, Draw_Temperature_Menu); + MENU_ITEM_F(ICON_Motion, MSG_MOTION, onDrawMotionSubMenu, Draw_Motion_Menu); + #if ENABLED(EEPROM_SETTINGS) + MENU_ITEM_F(ICON_WriteEEPROM, MSG_STORE_EEPROM, onDrawWriteEeprom, WriteEeprom); + MENU_ITEM_F(ICON_ReadEEPROM, MSG_LOAD_EEPROM, onDrawReadEeprom, ReadEeprom); + MENU_ITEM_F(ICON_ResumeEEPROM, MSG_RESTORE_DEFAULTS, onDrawResetEeprom, ResetEeprom); + #endif + MENU_ITEM_F(ICON_Reboot, MSG_RESET_PRINTER, onDrawMenuItem, RebootPrinter); #if ENABLED(CASE_LIGHT_MENU) #if ENABLED(CASELIGHT_USES_BRIGHTNESS) - MENU_ITEM(ICON_CaseLight, GET_TEXT_F(MSG_CASE_LIGHT), onDrawSubMenu, Draw_CaseLight_Menu); + MENU_ITEM_F(ICON_CaseLight, MSG_CASE_LIGHT, onDrawSubMenu, Draw_CaseLight_Menu); #else - MENU_ITEM(ICON_CaseLight, GET_TEXT_F(MSG_CASE_LIGHT), onDrawCaseLight, SetCaseLight); + MENU_ITEM_F(ICON_CaseLight, MSG_CASE_LIGHT, onDrawChkbMenu, SetCaseLight, &caselight.on); #endif #endif #if ENABLED(LED_CONTROL_MENU) - MENU_ITEM(ICON_LedControl, GET_TEXT_F(MSG_LED_CONTROL), onDrawSubMenu, Draw_LedControl_Menu); + MENU_ITEM_F(ICON_LedControl, MSG_LED_CONTROL, onDrawSubMenu, Draw_LedControl_Menu); #endif - MENU_ITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawTempSubMenu, Draw_Temperature_Menu); - MENU_ITEM(ICON_Motion, GET_TEXT_F(MSG_MOTION), onDrawMotionSubMenu, Draw_Motion_Menu); - #if ENABLED(EEPROM_SETTINGS) - MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); - MENU_ITEM(ICON_ReadEEPROM, GET_TEXT_F(MSG_LOAD_EEPROM), onDrawReadEeprom, ReadEeprom); - MENU_ITEM(ICON_ResumeEEPROM, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawResetEeprom, ResetEeprom); - #endif - MENU_ITEM(ICON_Reboot, GET_TEXT_F(MSG_RESET_PRINTER), onDrawMenuItem, RebootPrinter); - MENU_ITEM(ICON_Info, GET_TEXT_F(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_Info_Menu); + MENU_ITEM_F(ICON_Info, MSG_INFO_SCREEN, onDrawInfoSubMenu, Goto_Info_Menu); } ui.reset_status(true); CurrentMenu->draw(); @@ -3036,57 +3207,52 @@ void Draw_Control_Menu() { void Draw_AdvancedSettings_Menu() { checkkey = Menu; - if (!AdvancedSettings) AdvancedSettings = new MenuClass(); - if (CurrentMenu != AdvancedSettings) { - CurrentMenu = AdvancedSettings; - SetMenuTitle({0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG - DWINUI::MenuItemsPrepare(17); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + if (SetMenu(AdvancedSettings, GET_TEXT_F(MSG_ADVANCED_SETTINGS), 20)) { + BACK_ITEM(Goto_Main_Menu); #if ENABLED(EEPROM_SETTINGS) - MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); - #endif - #if HAS_HOME_OFFSET - MENU_ITEM(ICON_HomeOffset, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); + MENU_ITEM_F(ICON_WriteEEPROM, MSG_STORE_EEPROM, onDrawMenuItem, WriteEeprom); #endif #if HAS_BED_PROBE - MENU_ITEM(ICON_ProbeSet, GET_TEXT_F(MSG_ZPROBE_SETTINGS), onDrawSubMenu, Draw_ProbeSet_Menu); + MENU_ITEM_F(ICON_ProbeSet, MSG_ZPROBE_SETTINGS, onDrawSubMenu, Draw_ProbeSet_Menu); + #endif + #if HAS_MESH + MENU_ITEM_F(ICON_ProbeSet, MSG_MESH_LEVELING, onDrawSubMenu, Draw_MeshSet_Menu); + #endif + #if HAS_HOME_OFFSET + MENU_ITEM_F(ICON_HomeOffset, MSG_SET_HOME_OFFSETS, onDrawSubMenu, Draw_HomeOffset_Menu); #endif #if HAS_HOTEND - MENU_ITEM(ICON_PIDNozzle, F("Hotend PID Settings"), onDrawSubMenu, Draw_HotendPID_Menu); + MENU_ITEM(ICON_PIDNozzle, F(STR_HOTEND_PID " Settings"), onDrawSubMenu, Draw_HotendPID_Menu); #endif #if HAS_HEATED_BED - MENU_ITEM(ICON_PIDbed, F("Bed PID Settings"), onDrawSubMenu, Draw_BedPID_Menu); - #endif - #if HAS_FILAMENT_SENSOR - MENU_ITEM(ICON_FilSet, GET_TEXT_F(MSG_FILAMENT_SET), onDrawSubMenu, Draw_FilSet_Menu); + MENU_ITEM(ICON_PIDbed, F(STR_BED_PID " Settings"), onDrawSubMenu, Draw_BedPID_Menu); #endif + MENU_ITEM_F(ICON_FilSet, MSG_FILAMENT_SET, onDrawSubMenu, Draw_FilSet_Menu); #if ENABLED(POWER_LOSS_RECOVERY) - MENU_ITEM(ICON_Pwrlossr, GET_TEXT_F(MSG_OUTAGE_RECOVERY), onDrawPwrLossR, SetPwrLossr); + EDIT_ITEM_F(ICON_Pwrlossr, MSG_OUTAGE_RECOVERY, onDrawChkbMenu, SetPwrLossr, &recovery.enabled); #endif #if ENABLED(BAUD_RATE_GCODE) - MENU_ITEM(ICON_SetBaudRate, F("115K baud"), onDrawBaudrate, SetBaudRate); + EDIT_ITEM(ICON_SetBaudRate, F("115K baud"), onDrawChkbMenu, SetBaudRate, &HMI_data.Baud115K); #endif #if HAS_LCD_BRIGHTNESS - EDIT_ITEM(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); + EDIT_ITEM_F(ICON_Brightness, MSG_BRIGHTNESS, onDrawPInt8Menu, SetBrightness, &ui.brightness); + MENU_ITEM_F(ICON_Brightness, MSG_BRIGHTNESS_OFF, onDrawMenuItem, TurnOffBacklight); #endif - MENU_ITEM(ICON_Scolor, GET_TEXT_F(MSG_COLORS_SELECT), onDrawSubMenu, Draw_SelectColors_Menu); + MENU_ITEM_F(ICON_Scolor, MSG_COLORS_SELECT, onDrawSubMenu, Draw_SelectColors_Menu); #if ENABLED(SOUND_MENU_ITEM) - MENU_ITEM(ICON_Sound, GET_TEXT_F(MSG_SOUND_ENABLE), onDrawEnableSound, SetEnableSound); - #endif - #if HAS_MESH - MENU_ITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); + EDIT_ITEM_F(ICON_Sound, MSG_SOUND_ENABLE, onDrawChkbMenu, SetEnableSound, &ui.sound_on); #endif #if HAS_ESDIAG MENU_ITEM(ICON_ESDiag, F("End-stops diag."), onDrawSubMenu, Draw_EndStopDiag); #endif #if ENABLED(PRINTCOUNTER) - MENU_ITEM(ICON_PrintStats, GET_TEXT_F(MSG_INFO_STATS_MENU), onDrawSubMenu, Goto_PrintStats); - MENU_ITEM(ICON_PrintStatsReset, GET_TEXT_F(MSG_INFO_PRINT_COUNT_RESET), onDrawSubMenu, PrintStats.Reset); + MENU_ITEM_F(ICON_PrintStats, MSG_INFO_STATS_MENU, onDrawSubMenu, Goto_PrintStats); + MENU_ITEM_F(ICON_PrintStatsReset, MSG_INFO_PRINT_COUNT_RESET, onDrawSubMenu, PrintStats.Reset); #endif - MENU_ITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); + MENU_ITEM_F(ICON_Lock, MSG_LOCKSCREEN, onDrawMenuItem, DWIN_LockScreen); } ui.reset_status(true); - CurrentMenu->draw(); + UpdateMenu(AdvancedSettings); } void Draw_Move_Menu() { @@ -3095,181 +3261,146 @@ void Draw_Move_Menu() { if (CurrentMenu != MoveMenu) { CurrentMenu = MoveMenu; SetMenuTitle({192, 1, 42, 14}, GET_TEXT_F(MSG_MOVE_AXIS)); - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - EDIT_ITEM(ICON_MoveX, GET_TEXT_F(MSG_MOVE_X), onDrawMoveX, SetMoveX, ¤t_position.x); - EDIT_ITEM(ICON_MoveY, GET_TEXT_F(MSG_MOVE_Y), onDrawMoveY, SetMoveY, ¤t_position.y); - EDIT_ITEM(ICON_MoveZ, GET_TEXT_F(MSG_MOVE_Z), onDrawMoveZ, SetMoveZ, ¤t_position.z); + MenuItemsPrepare(5); + BACK_ITEM(Draw_Prepare_Menu); + EDIT_ITEM_F(ICON_MoveX, MSG_MOVE_X, onDrawMoveX, SetMoveX, ¤t_position.x); + EDIT_ITEM_F(ICON_MoveY, MSG_MOVE_Y, onDrawMoveY, SetMoveY, ¤t_position.y); + EDIT_ITEM_F(ICON_MoveZ, MSG_MOVE_Z, onDrawMoveZ, SetMoveZ, ¤t_position.z); #if HAS_HOTEND - EDIT_ITEM(ICON_Extruder, GET_TEXT_F(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e); + EDIT_ITEM_F(ICON_Extruder, MSG_MOVE_E, onDrawMoveE, SetMoveE, ¤t_position.e); #endif } CurrentMenu->draw(); - if (!all_axes_trusted()) LCD_MESSAGE_F("WARNING: current position is unknown, home axes"); + if (!all_axes_trusted()) LCD_MESSAGE_F("WARNING: Current position unknown. Home axes."); } #if HAS_HOME_OFFSET void Draw_HomeOffset_Menu() { checkkey = Menu; - if (!HomeOffMenu) HomeOffMenu = new MenuClass(); - if (CurrentMenu != HomeOffMenu) { - CurrentMenu = HomeOffMenu; - SetMenuTitle({0}, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // TODO: Chinese, English "Set Home Offsets" JPG - DWINUI::MenuItemsPrepare(4); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - EDIT_ITEM(ICON_HomeOffsetX, GET_TEXT_F(MSG_HOME_OFFSET_X), onDrawPFloatMenu, SetHomeOffsetX, &home_offset[X_AXIS]); - EDIT_ITEM(ICON_HomeOffsetY, GET_TEXT_F(MSG_HOME_OFFSET_Y), onDrawPFloatMenu, SetHomeOffsetY, &home_offset[Y_AXIS]); - EDIT_ITEM(ICON_HomeOffsetZ, GET_TEXT_F(MSG_HOME_OFFSET_Z), onDrawPFloatMenu, SetHomeOffsetZ, &home_offset[Z_AXIS]); + if (SetMenu(HomeOffMenu, GET_TEXT_F(MSG_SET_HOME_OFFSETS), 4)) { + BACK_ITEM(Draw_AdvancedSettings_Menu); + EDIT_ITEM_F(ICON_HomeOffsetX, MSG_HOME_OFFSET_X, onDrawPFloatMenu, SetHomeOffsetX, &home_offset.x); + EDIT_ITEM_F(ICON_HomeOffsetY, MSG_HOME_OFFSET_Y, onDrawPFloatMenu, SetHomeOffsetY, &home_offset.y); + EDIT_ITEM_F(ICON_HomeOffsetZ, MSG_HOME_OFFSET_Z, onDrawPFloatMenu, SetHomeOffsetZ, &home_offset.z); } - CurrentMenu->draw(); + UpdateMenu(HomeOffMenu); } #endif #if HAS_BED_PROBE void Draw_ProbeSet_Menu() { checkkey = Menu; - if (!ProbeSetMenu) ProbeSetMenu = new MenuClass(); - if (CurrentMenu != ProbeSetMenu) { - CurrentMenu = ProbeSetMenu; - SetMenuTitle({0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG - DWINUI::MenuItemsPrepare(9); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - EDIT_ITEM(ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); - EDIT_ITEM(ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); - EDIT_ITEM(ICON_ProbeOffsetZ, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); - #if BOTH(HAS_HEATED_BED, PREHEAT_BEFORE_LEVELING) - EDIT_ITEM(ICON_Temperature, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawPIntMenu, SetBedLevT, &HMI_data.BedLevT); - #endif + if (SetMenu(ProbeSetMenu, GET_TEXT_F(MSG_ZPROBE_SETTINGS), 8)) { + BACK_ITEM(Draw_AdvancedSettings_Menu); + EDIT_ITEM_F(ICON_ProbeOffsetX, MSG_ZPROBE_XOFFSET, onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); + EDIT_ITEM_F(ICON_ProbeOffsetY, MSG_ZPROBE_YOFFSET, onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); + EDIT_ITEM_F(ICON_ProbeOffsetZ, MSG_ZPROBE_ZOFFSET, onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); #ifdef BLTOUCH_HS_MODE - MENU_ITEM(ICON_HSMode, F("Enable HS mode"), onDrawHSMode, SetHSMode); + EDIT_ITEM_F(ICON_HSMode, MSG_ENABLE_HS_MODE, onDrawChkbMenu, SetHSMode, &bltouch.high_speed_mode); #endif - MENU_ITEM(ICON_ProbeTest, GET_TEXT_F(MSG_M48_TEST), onDrawMenuItem, ProbeTest); - MENU_ITEM(ICON_ProbeStow, GET_TEXT_F(MSG_MANUAL_STOW), onDrawMenuItem, ProbeStow); - MENU_ITEM(ICON_ProbeDeploy, GET_TEXT_F(MSG_MANUAL_DEPLOY), onDrawMenuItem, ProbeDeploy); + MENU_ITEM_F(ICON_ProbeTest, MSG_M48_TEST, onDrawMenuItem, ProbeTest); + MENU_ITEM_F(ICON_ProbeStow, MSG_MANUAL_STOW, onDrawMenuItem, ProbeStow); + MENU_ITEM_F(ICON_ProbeDeploy, MSG_MANUAL_DEPLOY, onDrawMenuItem, ProbeDeploy); } - CurrentMenu->draw(); + UpdateMenu(ProbeSetMenu); } + #endif -#if HAS_FILAMENT_SENSOR - void Draw_FilSet_Menu() { - checkkey = Menu; - if (!FilSetMenu) FilSetMenu = new MenuClass(); - if (CurrentMenu != FilSetMenu) { - CurrentMenu = FilSetMenu; - CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_FILAMENT_SET)); - DWINUI::MenuItemsPrepare(10); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); - #if HAS_FILAMENT_SENSOR - MENU_ITEM(ICON_Runout, GET_TEXT_F(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable); - #endif - #if HAS_FILAMENT_RUNOUT_DISTANCE - EDIT_ITEM(ICON_Runout, F("Runout Distance"), onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance()); - #endif - #if ENABLED(PREVENT_COLD_EXTRUSION) - EDIT_ITEM(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &HMI_data.ExtMinT); - #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) - EDIT_ITEM(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length); - EDIT_ITEM(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); - #endif - #if ENABLED(FWRETRACT) - EDIT_ITEM(ICON_FWRetLength, GET_TEXT_F(MSG_CONTROL_RETRACT), onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); - EDIT_ITEM(ICON_FWRetSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_RETRACT_SPEED), onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); - EDIT_ITEM(ICON_FWRetZRaise, GET_TEXT_F(MSG_CONTROL_RETRACT_ZHOP), onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); - EDIT_ITEM(ICON_FWRecSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_UNRETRACT_SPEED), onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); - #endif - } - CurrentMenu->draw(); +void Draw_FilSet_Menu() { + checkkey = Menu; + if (SetMenu(FilSetMenu, GET_TEXT_F(MSG_FILAMENT_SET), 9)) { + BACK_ITEM(Draw_AdvancedSettings_Menu); + #if HAS_FILAMENT_SENSOR + EDIT_ITEM_F(ICON_Runout, MSG_RUNOUT_ENABLE, onDrawChkbMenu, SetRunoutEnable, &runout.enabled); + #endif + #if HAS_FILAMENT_RUNOUT_DISTANCE + EDIT_ITEM_F(ICON_Runout, MSG_RUNOUT_DISTANCE_MM, onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance()); + #endif + #if ENABLED(PREVENT_COLD_EXTRUSION) + EDIT_ITEM_F(ICON_ExtrudeMinT, MSG_EXTRUDER_MIN_TEMP, onDrawPIntMenu, SetExtMinT, &HMI_data.ExtMinT); + #endif + #if ENABLED(ADVANCED_PAUSE_FEATURE) + EDIT_ITEM_F(ICON_FilLoad, MSG_FILAMENT_LOAD, onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length); + EDIT_ITEM_F(ICON_FilUnload, MSG_FILAMENT_UNLOAD, onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); + #endif + #if ENABLED(FWRETRACT) + MENU_ITEM_F(ICON_FWRetract, MSG_FWRETRACT, onDrawSubMenu, Draw_FWRetract_Menu); + #endif } -#endif // HAS_FILAMENT_SENSOR + UpdateMenu(FilSetMenu); +} void Draw_SelectColors_Menu() { checkkey = Menu; - if (!SelectColorMenu) SelectColorMenu = new MenuClass(); - if (CurrentMenu != SelectColorMenu) { - CurrentMenu = SelectColorMenu; - SetMenuTitle({0}, GET_TEXT_F(MSG_COLORS_SELECT)); // TODO: Chinese, English "Select Color" JPG - DWINUI::MenuItemsPrepare(20); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - MENU_ITEM(ICON_StockConfiguration, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawMenuItem, RestoreDefaultsColors); - EDIT_ITEM(0, "Screen Background", onDrawSelColorItem, SelColor, &HMI_data.Background_Color); - EDIT_ITEM(0, "Cursor", onDrawSelColorItem, SelColor, &HMI_data.Cursor_color); - EDIT_ITEM(0, "Title Background", onDrawSelColorItem, SelColor, &HMI_data.TitleBg_color); - EDIT_ITEM(0, "Title Text", onDrawSelColorItem, SelColor, &HMI_data.TitleTxt_color); - EDIT_ITEM(0, "Text", onDrawSelColorItem, SelColor, &HMI_data.Text_Color); - EDIT_ITEM(0, "Selected", onDrawSelColorItem, SelColor, &HMI_data.Selected_Color); - EDIT_ITEM(0, "Split Line", onDrawSelColorItem, SelColor, &HMI_data.SplitLine_Color); - EDIT_ITEM(0, "Highlight", onDrawSelColorItem, SelColor, &HMI_data.Highlight_Color); - EDIT_ITEM(0, "Status Background", onDrawSelColorItem, SelColor, &HMI_data.StatusBg_Color); - EDIT_ITEM(0, "Status Text", onDrawSelColorItem, SelColor, &HMI_data.StatusTxt_Color); - EDIT_ITEM(0, "Popup Background", onDrawSelColorItem, SelColor, &HMI_data.PopupBg_color); - EDIT_ITEM(0, "Popup Text", onDrawSelColorItem, SelColor, &HMI_data.PopupTxt_Color); - EDIT_ITEM(0, "Alert Background", onDrawSelColorItem, SelColor, &HMI_data.AlertBg_Color); - EDIT_ITEM(0, "Alert Text", onDrawSelColorItem, SelColor, &HMI_data.AlertTxt_Color); - EDIT_ITEM(0, "Percent Text", onDrawSelColorItem, SelColor, &HMI_data.PercentTxt_Color); - EDIT_ITEM(0, "Bar Fill", onDrawSelColorItem, SelColor, &HMI_data.Barfill_Color); - EDIT_ITEM(0, "Indicator value", onDrawSelColorItem, SelColor, &HMI_data.Indicator_Color); - EDIT_ITEM(0, "Coordinate value", onDrawSelColorItem, SelColor, &HMI_data.Coordinate_Color); - } - CurrentMenu->draw(); + if (SetMenu(SelectColorMenu, GET_TEXT_F(MSG_COLORS_SELECT), 20)) { + BACK_ITEM(Draw_AdvancedSettings_Menu); + MENU_ITEM_F(ICON_StockConfiguration, MSG_RESTORE_DEFAULTS, onDrawMenuItem, RestoreDefaultsColors); + EDIT_ITEM(0, F("Screen Background"), onDrawSelColorItem, SelColor, &HMI_data.Background_Color); + EDIT_ITEM(0, F("Cursor"), onDrawSelColorItem, SelColor, &HMI_data.Cursor_color); + EDIT_ITEM(0, F("Title Background"), onDrawSelColorItem, SelColor, &HMI_data.TitleBg_color); + EDIT_ITEM(0, F("Title Text"), onDrawSelColorItem, SelColor, &HMI_data.TitleTxt_color); + EDIT_ITEM(0, F("Text"), onDrawSelColorItem, SelColor, &HMI_data.Text_Color); + EDIT_ITEM(0, F("Selected"), onDrawSelColorItem, SelColor, &HMI_data.Selected_Color); + EDIT_ITEM(0, F("Split Line"), onDrawSelColorItem, SelColor, &HMI_data.SplitLine_Color); + EDIT_ITEM(0, F("Highlight"), onDrawSelColorItem, SelColor, &HMI_data.Highlight_Color); + EDIT_ITEM(0, F("Status Background"), onDrawSelColorItem, SelColor, &HMI_data.StatusBg_Color); + EDIT_ITEM(0, F("Status Text"), onDrawSelColorItem, SelColor, &HMI_data.StatusTxt_Color); + EDIT_ITEM(0, F("Popup Background"), onDrawSelColorItem, SelColor, &HMI_data.PopupBg_color); + EDIT_ITEM(0, F("Popup Text"), onDrawSelColorItem, SelColor, &HMI_data.PopupTxt_Color); + EDIT_ITEM(0, F("Alert Background"), onDrawSelColorItem, SelColor, &HMI_data.AlertBg_Color); + EDIT_ITEM(0, F("Alert Text"), onDrawSelColorItem, SelColor, &HMI_data.AlertTxt_Color); + EDIT_ITEM(0, F("Percent Text"), onDrawSelColorItem, SelColor, &HMI_data.PercentTxt_Color); + EDIT_ITEM(0, F("Bar Fill"), onDrawSelColorItem, SelColor, &HMI_data.Barfill_Color); + EDIT_ITEM(0, F("Indicator value"), onDrawSelColorItem, SelColor, &HMI_data.Indicator_Color); + EDIT_ITEM(0, F("Coordinate value"), onDrawSelColorItem, SelColor, &HMI_data.Coordinate_Color); + } + UpdateMenu(SelectColorMenu); } void Draw_GetColor_Menu() { checkkey = Menu; - if (!GetColorMenu) GetColorMenu = new MenuClass(); - if (CurrentMenu != GetColorMenu) { - CurrentMenu = GetColorMenu; - SetMenuTitle({0}, GET_TEXT_F(MSG_COLORS_GET)); // TODO: Chinese, English "Get Color" JPG - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); - MENU_ITEM(ICON_Cancel, GET_TEXT_F(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); - MENU_ITEM(0, GET_TEXT_F(MSG_COLORS_RED), onDrawGetColorItem, SetRGBColor); - MENU_ITEM(1, GET_TEXT_F(MSG_COLORS_GREEN), onDrawGetColorItem, SetRGBColor); - MENU_ITEM(2, GET_TEXT_F(MSG_COLORS_BLUE), onDrawGetColorItem, SetRGBColor); - } - CurrentMenu->draw(); + if (SetMenu(GetColorMenu, GET_TEXT_F(MSG_COLORS_GET), 5)) { + BACK_ITEM(DWIN_ApplyColor); + MENU_ITEM_F(ICON_Cancel, MSG_BUTTON_CANCEL, onDrawMenuItem, Draw_SelectColors_Menu); + MENU_ITEM_F(0, MSG_COLORS_RED, onDrawGetColorItem, SetRGBColor); + MENU_ITEM_F(1, MSG_COLORS_GREEN, onDrawGetColorItem, SetRGBColor); + MENU_ITEM_F(2, MSG_COLORS_BLUE, onDrawGetColorItem, SetRGBColor); + } + UpdateMenu(GetColorMenu); DWIN_Draw_Rectangle(1, *MenuData.P_Int, 20, 315, DWIN_WIDTH - 20, 335); } #if BOTH(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) void Draw_CaseLight_Menu() { checkkey = Menu; - if (!CaseLightMenu) CaseLightMenu = new MenuClass(); - if (CurrentMenu != CaseLightMenu) { - CurrentMenu = CaseLightMenu; - SetMenuTitle({0}, GET_TEXT_F(MSG_CASE_LIGHT)); // TODO: Chinese, English "Case Light" JPG - DWINUI::MenuItemsPrepare(3); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); - MENU_ITEM(ICON_CaseLight, GET_TEXT_F(MSG_CASE_LIGHT), onDrawCaseLight, SetCaseLight); - EDIT_ITEM(ICON_Brightness, GET_TEXT_F(MSG_CASE_LIGHT_BRIGHTNESS), onDrawPInt8Menu, SetCaseLightBrightness, &caselight.brightness); + if (SetMenu(CaseLightMenu, GET_TEXT_F(MSG_CASE_LIGHT), 3)) { + BACK_ITEM(Draw_Control_Menu); + EDIT_ITEM_F(ICON_CaseLight, MSG_CASE_LIGHT, onDrawChkbMenu, SetCaseLight, &caselight.on); + EDIT_ITEM_F(ICON_Brightness, MSG_CASE_LIGHT_BRIGHTNESS, onDrawPInt8Menu, SetCaseLightBrightness, &caselight.brightness); } - CurrentMenu->draw(); + UpdateMenu(CaseLightMenu); } #endif #if ENABLED(LED_CONTROL_MENU) void Draw_LedControl_Menu() { checkkey = Menu; - if (!LedControlMenu) LedControlMenu = new MenuClass(); - if (CurrentMenu != LedControlMenu) { - CurrentMenu = LedControlMenu; - SetMenuTitle({0}, GET_TEXT_F(MSG_LED_CONTROL)); // TODO: Chinese, English "LED Control" JPG - DWINUI::MenuItemsPrepare(6); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + if (SetMenu(LedControlMenu, GET_TEXT_F(MSG_LED_CONTROL), 6)) { + BACK_ITEM(Draw_Control_Menu); #if !BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) - MENU_ITEM(ICON_LedControl, GET_TEXT_F(MSG_LEDS), onDrawLedStatus, SetLedStatus); + EDIT_ITEM_F(ICON_LedControl, MSG_LEDS, onDrawChkbMenu, SetLedStatus, &leds.lights_on); #endif - #if (HAS_COLOR_LEDS) - EDIT_ITEM(ICON_LedControl, GET_TEXT_F(MSG_COLORS_RED), onDrawPInt8Menu, SetLedColorR, &leds.color.r); - EDIT_ITEM(ICON_LedControl, GET_TEXT_F(MSG_COLORS_GREEN), onDrawPInt8Menu, SetLedColorG, &leds.color.g); - EDIT_ITEM(ICON_LedControl, GET_TEXT_F(MSG_COLORS_BLUE), onDrawPInt8Menu, SetLedColorB, &leds.color.b); + #if HAS_COLOR_LEDS + EDIT_ITEM_F(ICON_LedControl, MSG_COLORS_RED, onDrawPInt8Menu, SetLEDColorR, &leds.color.r); + EDIT_ITEM_F(ICON_LedControl, MSG_COLORS_GREEN, onDrawPInt8Menu, SetLEDColorG, &leds.color.g); + EDIT_ITEM_F(ICON_LedControl, MSG_COLORS_BLUE, onDrawPInt8Menu, SetLEDColorB, &leds.color.b); #if ENABLED(HAS_WHITE_LED) - EDIT_ITEM(ICON_LedControl, GET_TEXT_F(MSG_COLORS_WHITE), onDrawPInt8Menu, SetLedColorW, &leds.color.w); + EDIT_ITEM_F(ICON_LedControl, MSG_COLORS_WHITE, onDrawPInt8Menu, SetLedColorW, &leds.color.w); #endif #endif } - CurrentMenu->draw(); + UpdateMenu(LedControlMenu); } #endif @@ -3279,40 +3410,37 @@ void Draw_Tune_Menu() { if (CurrentMenu != TuneMenu) { CurrentMenu = TuneMenu; SetMenuTitle({73, 2, 28, 12}, GET_TEXT_F(MSG_TUNE)); // TODO: Chinese, English "Tune" JPG - DWINUI::MenuItemsPrepare(16); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); - #if ENABLED(CASE_LIGHT_MENU) - MENU_ITEM(ICON_CaseLight, GET_TEXT_F(MSG_CASE_LIGHT), onDrawCaseLight, SetCaseLight); - #elif ENABLED(LED_CONTROL_MENU) && DISABLED(CASE_LIGHT_USE_NEOPIXEL) - MENU_ITEM(ICON_LedControl, GET_TEXT_F(MSG_LEDS), onDrawLedStatus, SetLedStatus); - #endif - EDIT_ITEM(ICON_Speed, GET_TEXT_F(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); + MenuItemsPrepare(16); + BACK_ITEM(Goto_PrintProcess); + EDIT_ITEM_F(ICON_Speed, MSG_SPEED, onDrawSpeedItem, SetSpeed, &feedrate_percentage); #if HAS_HOTEND - HotendTargetItem = EDIT_ITEM(ICON_HotendTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); + HotendTargetItem = EDIT_ITEM_F(ICON_HotendTemp, MSG_UBL_SET_TEMP_HOTEND, onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED - BedTargetItem = EDIT_ITEM(ICON_BedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); + BedTargetItem = EDIT_ITEM_F(ICON_BedTemp, MSG_UBL_SET_TEMP_BED, onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); #endif #if HAS_FAN - FanSpeedItem = EDIT_ITEM(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); - #endif - #if HAS_ZOFFSET_ITEM && EITHER(HAS_BED_PROBE, BABYSTEPPING) - EDIT_ITEM(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); + FanSpeedItem = EDIT_ITEM_F(ICON_FanSpeed, MSG_FAN_SPEED, onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); #endif - #if ENABLED(FWRETRACT) - EDIT_ITEM(ICON_FWRetLength, GET_TEXT_F(MSG_CONTROL_RETRACT), onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); - EDIT_ITEM(ICON_FWRetSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_RETRACT_SPEED), onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); - EDIT_ITEM(ICON_FWRetZRaise, GET_TEXT_F(MSG_CONTROL_RETRACT_ZHOP), onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); - EDIT_ITEM(ICON_FWRecSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_UNRETRACT_SPEED), onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); + #if HAS_ZOFFSET_ITEM && EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + EDIT_ITEM_F(ICON_Zoffset, MSG_ZPROBE_ZOFFSET, onDrawZOffset, SetZOffset, &BABY_Z_VAR); #endif - EDIT_ITEM(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); + EDIT_ITEM_F(ICON_Flow, MSG_FLOW, onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); #if ENABLED(ADVANCED_PAUSE_FEATURE) - MENU_ITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); + MENU_ITEM_F(ICON_FilMan, MSG_FILAMENTCHANGE, onDrawMenuItem, ChangeFilament); + #endif + #if ENABLED(FWRETRACT) + MENU_ITEM_F(ICON_FWRetract, MSG_FWRETRACT, onDrawSubMenu, Draw_FWRetract_Menu); #endif - MENU_ITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); + MENU_ITEM_F(ICON_Lock, MSG_LOCKSCREEN, onDrawMenuItem, DWIN_LockScreen); #if HAS_LCD_BRIGHTNESS - EDIT_ITEM(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); - MENU_ITEM(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS_OFF), onDrawMenuItem, TurnOffBacklight); + EDIT_ITEM_F(ICON_Brightness, MSG_BRIGHTNESS, onDrawPInt8Menu, SetBrightness, &ui.brightness); + MENU_ITEM_F(ICON_Brightness, MSG_BRIGHTNESS_OFF, onDrawMenuItem, TurnOffBacklight); + #endif + #if ENABLED(CASE_LIGHT_MENU) + EDIT_ITEM_F(ICON_CaseLight, MSG_CASE_LIGHT, onDrawChkbMenu, SetCaseLight, &caselight.on); + #elif ENABLED(LED_CONTROL_MENU) && DISABLED(CASE_LIGHT_USE_NEOPIXEL) + EDIT_ITEM_F(ICON_LedControl, MSG_LEDS, onDrawChkbMenu, SetLedStatus, &leds.lights_on); #endif } CurrentMenu->draw(); @@ -3324,15 +3452,15 @@ void Draw_Motion_Menu() { if (CurrentMenu != MotionMenu) { CurrentMenu = MotionMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MOTION)); // TODO: Chinese, English "Motion" JPG - DWINUI::MenuItemsPrepare(6); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); - MENU_ITEM(ICON_MaxSpeed, GET_TEXT_F(MSG_SPEED), onDrawSpeed, Draw_MaxSpeed_Menu); - MENU_ITEM(ICON_MaxAccelerated, GET_TEXT_F(MSG_ACCELERATION), onDrawAcc, Draw_MaxAccel_Menu); + MenuItemsPrepare(6); + BACK_ITEM(Draw_Control_Menu); + MENU_ITEM_F(ICON_MaxSpeed, MSG_SPEED, onDrawSpeed, Draw_MaxSpeed_Menu); + MENU_ITEM_F(ICON_MaxAccelerated, MSG_ACCELERATION, onDrawAcc, Draw_MaxAccel_Menu); #if HAS_CLASSIC_JERK - MENU_ITEM(ICON_MaxJerk, GET_TEXT_F(MSG_JERK), onDrawJerk, Draw_MaxJerk_Menu); + MENU_ITEM_F(ICON_MaxJerk, MSG_JERK, onDrawJerk, Draw_MaxJerk_Menu); #endif - MENU_ITEM(ICON_Step, GET_TEXT_F(MSG_STEPS_PER_MM), onDrawSteps, Draw_Steps_Menu); - EDIT_ITEM(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); + MENU_ITEM_F(ICON_Step, MSG_STEPS_PER_MM, onDrawSteps, Draw_Steps_Menu); + EDIT_ITEM_F(ICON_Flow, MSG_FLOW, onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); } CurrentMenu->draw(); } @@ -3340,39 +3468,31 @@ void Draw_Motion_Menu() { #if ENABLED(ADVANCED_PAUSE_FEATURE) void Draw_FilamentMan_Menu() { checkkey = Menu; - if (!FilamentMenu) FilamentMenu = new MenuClass(); - if (CurrentMenu != FilamentMenu) { - CurrentMenu = FilamentMenu; - SetMenuTitle({0}, GET_TEXT_F(MSG_FILAMENT_MAN)); // TODO: Chinese, English "Filament Management" JPG - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - MENU_ITEM(ICON_Park, GET_TEXT_F(MSG_FILAMENT_PARK_ENABLED), onDrawMenuItem, ParkHead); - MENU_ITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); + if (SetMenu(FilamentMenu, GET_TEXT_F(MSG_FILAMENT_MAN), 5)) { + BACK_ITEM(Draw_Prepare_Menu); + MENU_ITEM_F(ICON_Park, MSG_FILAMENT_PARK_ENABLED, onDrawMenuItem, ParkHead); + MENU_ITEM_F(ICON_FilMan, MSG_FILAMENTCHANGE, onDrawMenuItem, ChangeFilament); #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - MENU_ITEM(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENTUNLOAD), onDrawMenuItem, UnloadFilament); - MENU_ITEM(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament); + MENU_ITEM_F(ICON_FilUnload, MSG_FILAMENTUNLOAD, onDrawMenuItem, UnloadFilament); + MENU_ITEM_F(ICON_FilLoad, MSG_FILAMENTLOAD, onDrawMenuItem, LoadFilament); #endif } - CurrentMenu->draw(); + UpdateMenu(FilamentMenu); } #endif #if ENABLED(MESH_BED_LEVELING) void Draw_ManualMesh_Menu() { checkkey = Menu; - if (!ManualMesh) ManualMesh = new MenuClass(); - if (CurrentMenu != ManualMesh) { - CurrentMenu = ManualMesh; - SetMenuTitle({0}, GET_TEXT_F(MSG_MANUAL_MESH)); // TODO: Chinese, English "Manual Mesh Leveling" JPG - DWINUI::MenuItemsPrepare(6); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - MENU_ITEM(ICON_ManualMesh, GET_TEXT_F(MSG_LEVEL_BED), onDrawMenuItem, ManualMeshStart); - MMeshMoveZItem = EDIT_ITEM(ICON_Zoffset, GET_TEXT_F(MSG_MOVE_Z), onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); - MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_UBL_CONTINUE_MESH), onDrawMenuItem, ManualMeshContinue); - MENU_ITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); - MENU_ITEM(ICON_MeshSave, GET_TEXT_F(MSG_UBL_SAVE_MESH), onDrawMenuItem, ManualMeshSave); + if (SetMenu(ManualMesh, GET_TEXT_F(MSG_UBL_MANUAL_MESH), 6)) { + BACK_ITEM(Draw_Prepare_Menu); + MENU_ITEM_F(ICON_ManualMesh, MSG_LEVEL_BED, onDrawMenuItem, ManualMeshStart); + MMeshMoveZItem = EDIT_ITEM_F(ICON_Zoffset, MSG_MOVE_Z, onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); + MENU_ITEM_F(ICON_Axis, MSG_UBL_CONTINUE_MESH, onDrawMenuItem, ManualMeshContinue); + MENU_ITEM_F(ICON_MeshViewer, MSG_MESH_VIEW, onDrawSubMenu, DWIN_MeshViewer); + MENU_ITEM_F(ICON_MeshSave, MSG_UBL_SAVE_MESH, onDrawMenuItem, ManualMeshSave); } - CurrentMenu->draw(); + UpdateMenu(ManualMesh); } #endif @@ -3383,42 +3503,43 @@ void Draw_Motion_Menu() { if (CurrentMenu != PreheatMenu) { CurrentMenu = PreheatMenu; SetMenuTitle(cn, fstr); - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); + MenuItemsPrepare(5); + BACK_ITEM(Draw_Temperature_Menu); #if HAS_HOTEND - EDIT_ITEM(ICON_SetEndTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Preheat].hotend_temp); + EDIT_ITEM_F(ICON_SetEndTemp, MSG_UBL_SET_TEMP_HOTEND, onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Select].hotend_temp); #endif #if HAS_HEATED_BED - EDIT_ITEM(ICON_SetBedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Preheat].bed_temp); + EDIT_ITEM_F(ICON_SetBedTemp, MSG_UBL_SET_TEMP_BED, onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Select].bed_temp); #endif #if HAS_FAN - EDIT_ITEM(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Preheat].fan_speed); + EDIT_ITEM_F(ICON_FanSpeed, MSG_FAN_SPEED, onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Select].fan_speed); #endif #if ENABLED(EEPROM_SETTINGS) - MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); + MENU_ITEM_F(ICON_WriteEEPROM, MSG_STORE_EEPROM, onDrawWriteEeprom, WriteEeprom); #endif } CurrentMenu->draw(); } void Draw_Preheat1_Menu() { - HMI_value.Preheat = 0; + HMI_value.Select = 0; if (!PreheatMenu) PreheatMenu = new MenuClass(); Draw_Preheat_Menu({59, 16, 81, 14}, F(PREHEAT_1_LABEL " Preheat Settings")); // TODO: English "PLA Settings" JPG } - void Draw_Preheat2_Menu() { - HMI_value.Preheat = 1; - if (!PreheatMenu) PreheatMenu = new MenuClass(); - Draw_Preheat_Menu({142, 16, 82, 14}, F(PREHEAT_2_LABEL " Preheat Settings")); // TODO: English "ABS Settings" JPG - } + #if PREHEAT_COUNT >= 2 + void Draw_Preheat2_Menu() { + HMI_value.Select = 1; + if (!PreheatMenu) PreheatMenu = new MenuClass(); + Draw_Preheat_Menu({142, 16, 82, 14}, F(PREHEAT_2_LABEL " Preheat Settings")); // TODO: English "ABS Settings" JPG + } + #endif - #ifdef PREHEAT_3_LABEL + #if PREHEAT_COUNT >= 3 void Draw_Preheat3_Menu() { - HMI_value.Preheat = 2; + HMI_value.Select = 2; if (!PreheatMenu) PreheatMenu = new MenuClass(); - #define PREHEAT_3_TITLE PREHEAT_3_LABEL " Preheat Set." - Draw_Preheat_Menu({0}, F(PREHEAT_3_TITLE)); // TODO: Chinese, English "Custom Preheat Settings" JPG + Draw_Preheat_Menu({225, 16, 82, 14}, F(PREHEAT_3_LABEL " Preheat Settings")); // TODO: English "... Settings" JPG } #endif @@ -3430,22 +3551,24 @@ void Draw_Temperature_Menu() { if (CurrentMenu != TemperatureMenu) { CurrentMenu = TemperatureMenu; SetMenuTitle({236, 2, 28, 12}, GET_TEXT_F(MSG_TEMPERATURE)); - DWINUI::MenuItemsPrepare(7); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + MenuItemsPrepare(7); + BACK_ITEM(Draw_Control_Menu); #if HAS_HOTEND - HotendTargetItem = EDIT_ITEM(ICON_SetEndTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); + HotendTargetItem = EDIT_ITEM_F(ICON_SetEndTemp, MSG_UBL_SET_TEMP_HOTEND, onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED - BedTargetItem = EDIT_ITEM(ICON_SetBedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); + BedTargetItem = EDIT_ITEM_F(ICON_SetBedTemp, MSG_UBL_SET_TEMP_BED, onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); #endif #if HAS_FAN - FanSpeedItem = EDIT_ITEM(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); + FanSpeedItem = EDIT_ITEM_F(ICON_FanSpeed, MSG_FAN_SPEED, onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); #endif - #if HAS_HOTEND - MENU_ITEM(ICON_SetPLAPreheat, F(PREHEAT_1_LABEL " Preheat Settings"), onDrawPLAPreheatSubMenu, Draw_Preheat1_Menu); - MENU_ITEM(ICON_SetABSPreheat, F(PREHEAT_2_LABEL " Preheat Settings"), onDrawABSPreheatSubMenu, Draw_Preheat2_Menu); - #ifdef PREHEAT_3_LABEL - MENU_ITEM(ICON_SetCustomPreheat, PREHEAT_3_TITLE, onDrawSubMenu, Draw_Preheat3_Menu); + #if HAS_PREHEAT + MENU_ITEM_F(ICON_SetPLAPreheat, MSG_PREHEAT_1_SETTINGS, onDrawPLAPreheatSubMenu, Draw_Preheat1_Menu); + #if PREHEAT_COUNT >= 2 + MENU_ITEM_F(ICON_SetABSPreheat, MSG_PREHEAT_2_SETTINGS, onDrawABSPreheatSubMenu, Draw_Preheat2_Menu); + #if PREHEAT_COUNT >= 3 + MENU_ITEM_F(ICON_SetCustomPreheat, MSG_PREHEAT_3_SETTINGS, onDrawSubMenu, Draw_Preheat3_Menu); + #endif #endif #endif } @@ -3457,14 +3580,14 @@ void Draw_MaxSpeed_Menu() { if (!MaxSpeedMenu) MaxSpeedMenu = new MenuClass(); if (CurrentMenu != MaxSpeedMenu) { CurrentMenu = MaxSpeedMenu; - SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MAXSPEED)); - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - EDIT_ITEM(ICON_MaxSpeedX, GET_TEXT_F(MSG_MAXSPEED_X), onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); - EDIT_ITEM(ICON_MaxSpeedY, GET_TEXT_F(MSG_MAXSPEED_Y), onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); - EDIT_ITEM(ICON_MaxSpeedZ, GET_TEXT_F(MSG_MAXSPEED_Z), onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); + SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MAX_SPEED)); + MenuItemsPrepare(5); + BACK_ITEM(Draw_Motion_Menu); + EDIT_ITEM_F(ICON_MaxSpeedX, MSG_VMAX_A, onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); + EDIT_ITEM_F(ICON_MaxSpeedY, MSG_VMAX_B, onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); + EDIT_ITEM_F(ICON_MaxSpeedZ, MSG_VMAX_C, onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); #if HAS_HOTEND - EDIT_ITEM(ICON_MaxSpeedE, GET_TEXT_F(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[E_AXIS]); + EDIT_ITEM_F(ICON_MaxSpeedE, MSG_VMAX_E, onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3476,13 +3599,13 @@ void Draw_MaxAccel_Menu() { if (CurrentMenu != MaxAccelMenu) { CurrentMenu = MaxAccelMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_ACCELERATION)); - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - EDIT_ITEM(ICON_MaxAccX, GET_TEXT_F(MSG_AMAX_A), onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - EDIT_ITEM(ICON_MaxAccY, GET_TEXT_F(MSG_AMAX_B), onDrawMaxAccelY, SetMaxAccelY, &planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - EDIT_ITEM(ICON_MaxAccZ, GET_TEXT_F(MSG_AMAX_C), onDrawMaxAccelZ, SetMaxAccelZ, &planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); + MenuItemsPrepare(5); + BACK_ITEM(Draw_Motion_Menu); + EDIT_ITEM_F(ICON_MaxAccX, MSG_AMAX_A, onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); + EDIT_ITEM_F(ICON_MaxAccY, MSG_AMAX_B, onDrawMaxAccelY, SetMaxAccelY, &planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + EDIT_ITEM_F(ICON_MaxAccZ, MSG_AMAX_C, onDrawMaxAccelZ, SetMaxAccelZ, &planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); #if HAS_HOTEND - EDIT_ITEM(ICON_MaxAccE, GET_TEXT_F(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + EDIT_ITEM_F(ICON_MaxAccE, MSG_AMAX_E, onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3495,13 +3618,13 @@ void Draw_MaxAccel_Menu() { if (CurrentMenu != MaxJerkMenu) { CurrentMenu = MaxJerkMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_JERK)); - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - EDIT_ITEM(ICON_MaxSpeedJerkX, GET_TEXT_F(MSG_VA_JERK), onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); - EDIT_ITEM(ICON_MaxSpeedJerkY, GET_TEXT_F(MSG_VB_JERK), onDrawMaxJerkY, SetMaxJerkY, &planner.max_jerk[Y_AXIS]); - EDIT_ITEM(ICON_MaxSpeedJerkZ, GET_TEXT_F(MSG_VC_JERK), onDrawMaxJerkZ, SetMaxJerkZ, &planner.max_jerk[Z_AXIS]); + MenuItemsPrepare(5); + BACK_ITEM(Draw_Motion_Menu); + EDIT_ITEM_F(ICON_MaxSpeedJerkX, MSG_VA_JERK, onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); + EDIT_ITEM_F(ICON_MaxSpeedJerkY, MSG_VB_JERK, onDrawMaxJerkY, SetMaxJerkY, &planner.max_jerk[Y_AXIS]); + EDIT_ITEM_F(ICON_MaxSpeedJerkZ, MSG_VC_JERK, onDrawMaxJerkZ, SetMaxJerkZ, &planner.max_jerk[Z_AXIS]); #if HAS_HOTEND - EDIT_ITEM(ICON_MaxSpeedJerkE, GET_TEXT_F(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS]); + EDIT_ITEM_F(ICON_MaxSpeedJerkE, MSG_VE_JERK, onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3514,13 +3637,13 @@ void Draw_Steps_Menu() { if (CurrentMenu != StepsMenu) { CurrentMenu = StepsMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_STEPS_PER_MM)); - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - EDIT_ITEM(ICON_StepX, GET_TEXT_F(MSG_A_STEPS), onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); - EDIT_ITEM(ICON_StepY, GET_TEXT_F(MSG_B_STEPS), onDrawStepsY, SetStepsY, &planner.settings.axis_steps_per_mm[Y_AXIS]); - EDIT_ITEM(ICON_StepZ, GET_TEXT_F(MSG_C_STEPS), onDrawStepsZ, SetStepsZ, &planner.settings.axis_steps_per_mm[Z_AXIS]); + MenuItemsPrepare(5); + BACK_ITEM(Draw_Motion_Menu); + EDIT_ITEM_F(ICON_StepX, MSG_A_STEPS, onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); + EDIT_ITEM_F(ICON_StepY, MSG_B_STEPS, onDrawStepsY, SetStepsY, &planner.settings.axis_steps_per_mm[Y_AXIS]); + EDIT_ITEM_F(ICON_StepZ, MSG_C_STEPS, onDrawStepsZ, SetStepsZ, &planner.settings.axis_steps_per_mm[Z_AXIS]); #if HAS_HOTEND - EDIT_ITEM(ICON_StepE, GET_TEXT_F(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS]); + EDIT_ITEM_F(ICON_StepE, MSG_E_STEPS, onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3529,63 +3652,51 @@ void Draw_Steps_Menu() { #if HAS_HOTEND void Draw_HotendPID_Menu() { checkkey = Menu; - if (!HotendPIDMenu) HotendPIDMenu = new MenuClass(); - if (CurrentMenu != HotendPIDMenu) { - CurrentMenu = HotendPIDMenu; - CurrentMenu->MenuTitle.SetCaption(F("Hotend PID Settings")); - DWINUI::MenuItemsPrepare(8); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); - MENU_ITEM(ICON_PIDNozzle, F("Hotend PID"), onDrawMenuItem, HotendPID); + if (SetMenu(HotendPIDMenu, F(STR_HOTEND_PID " Settings"),8)) { + BACK_ITEM(Draw_AdvancedSettings_Menu); + MENU_ITEM(ICON_PIDNozzle, F(STR_HOTEND_PID), onDrawMenuItem, HotendPID); EDIT_ITEM(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_hotend[0].pid.Kp); EDIT_ITEM(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_hotend[0].pid.Ki); EDIT_ITEM(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_hotend[0].pid.Kd); - EDIT_ITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); - EDIT_ITEM(ICON_PIDcycles, GET_TEXT_F(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); + EDIT_ITEM_F(ICON_Temperature, MSG_TEMPERATURE, onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); + EDIT_ITEM_F(ICON_PIDcycles, MSG_PID_CYCLE, onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); #if ENABLED(EEPROM_SETTINGS) - MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + MENU_ITEM_F(ICON_WriteEEPROM, MSG_STORE_EEPROM, onDrawMenuItem, WriteEeprom); #endif } - CurrentMenu->draw(); + UpdateMenu(HotendPIDMenu); } #endif #if HAS_HEATED_BED void Draw_BedPID_Menu() { checkkey = Menu; - if (!BedPIDMenu) BedPIDMenu = new MenuClass(); - if (CurrentMenu != BedPIDMenu) { - CurrentMenu = BedPIDMenu; - CurrentMenu->MenuTitle.SetCaption(F("Bed PID Settings")); - DWINUI::MenuItemsPrepare(8); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); - MENU_ITEM(ICON_PIDNozzle, F("Bed PID"), onDrawMenuItem,BedPID); + if (SetMenu(BedPIDMenu, F(STR_BED_PID " Settings"),8)) { + BACK_ITEM(Draw_AdvancedSettings_Menu); + MENU_ITEM(ICON_PIDNozzle, F(STR_BED_PID), onDrawMenuItem,BedPID); EDIT_ITEM(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_bed.pid.Kp); EDIT_ITEM(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_bed.pid.Ki); EDIT_ITEM(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_bed.pid.Kd); - EDIT_ITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); - EDIT_ITEM(ICON_PIDcycles, GET_TEXT_F(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); + EDIT_ITEM_F(ICON_Temperature, MSG_TEMPERATURE, onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); + EDIT_ITEM_F(ICON_PIDcycles, MSG_PID_CYCLE, onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); #if ENABLED(EEPROM_SETTINGS) - MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + MENU_ITEM_F(ICON_WriteEEPROM, MSG_STORE_EEPROM, onDrawMenuItem, WriteEeprom); #endif } - CurrentMenu->draw(); + UpdateMenu(BedPIDMenu); } #endif -#if HAS_BED_PROBE +#if ENABLED(BABYSTEP_ZPROBE_OFFSET) void Draw_ZOffsetWiz_Menu() { checkkey = Menu; - if (!ZOffsetWizMenu) ZOffsetWizMenu = new MenuClass(); - if (CurrentMenu != ZOffsetWizMenu) { - CurrentMenu = ZOffsetWizMenu; - CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_PROBE_WIZARD)); - DWINUI::MenuItemsPrepare(4); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); - MENU_ITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); + if (SetMenu(ZOffsetWizMenu, GET_TEXT_F(MSG_PROBE_WIZARD), 4)) { + BACK_ITEM(Draw_Prepare_Menu); + MENU_ITEM_F(ICON_Homing, MSG_AUTO_HOME, onDrawMenuItem, AutoHome); MENU_ITEM(ICON_MoveZ0, F("Move Z to Home"), onDrawMenuItem, SetMoveZto0); - EDIT_ITEM(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); + EDIT_ITEM_F(ICON_Zoffset, MSG_ZPROBE_ZOFFSET, onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); } - CurrentMenu->draw(); + UpdateMenu(ZOffsetWizMenu); if (!axis_is_trusted(Z_AXIS)) LCD_MESSAGE_F("WARNING: Z position unknown, move Z to home"); } #endif @@ -3593,19 +3704,165 @@ void Draw_Steps_Menu() { #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) void Draw_Homing_Menu() { checkkey = Menu; - if (!HomingMenu) HomingMenu = new MenuClass(); - if (CurrentMenu != HomingMenu) { - CurrentMenu = HomingMenu; - CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_HOMING)); - DWINUI::MenuItemsPrepare(5); - MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); - MENU_ITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); - MENU_ITEM(ICON_HomeX, GET_TEXT_F(MSG_AUTO_HOME_X), onDrawMenuItem, HomeX); - MENU_ITEM(ICON_HomeY, GET_TEXT_F(MSG_AUTO_HOME_Y), onDrawMenuItem, HomeY); - MENU_ITEM(ICON_HomeZ, GET_TEXT_F(MSG_AUTO_HOME_Z), onDrawMenuItem, HomeZ); + if (SetMenu(HomingMenu, GET_TEXT_F(MSG_HOMING), 5)) { + BACK_ITEM(Draw_Prepare_Menu); + MENU_ITEM_F(ICON_Homing, MSG_AUTO_HOME, onDrawMenuItem, AutoHome); + MENU_ITEM_F(ICON_HomeX, MSG_AUTO_HOME_X, onDrawMenuItem, HomeX); + MENU_ITEM_F(ICON_HomeY, MSG_AUTO_HOME_Y, onDrawMenuItem, HomeY); + MENU_ITEM_F(ICON_HomeZ, MSG_AUTO_HOME_Z, onDrawMenuItem, HomeZ); } - CurrentMenu->draw(); + UpdateMenu(HomingMenu); + } +#endif + +#if ENABLED(FWRETRACT) + void Draw_FWRetract_Menu() { + checkkey = Menu; + if (SetMenu(FWRetractMenu, GET_TEXT_F(MSG_FWRETRACT), 6)) { + BACK_ITEM(Return_FWRetract_Menu); + EDIT_ITEM_F(ICON_FWRetLength, MSG_CONTROL_RETRACT, onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); + EDIT_ITEM_F(ICON_FWRetSpeed, MSG_SINGLENOZZLE_RETRACT_SPEED, onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); + EDIT_ITEM_F(ICON_FWRetZRaise, MSG_CONTROL_RETRACT_ZHOP, onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); + EDIT_ITEM_F(ICON_FWRecSpeed, MSG_SINGLENOZZLE_UNRETRACT_SPEED, onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); + EDIT_ITEM_F(ICON_FWRecExtra, MSG_CONTROL_RETRACT_RECOVER, onDrawPFloatMenu, SetAddRecover, &fwretract.settings.retract_recover_extra); + } + UpdateMenu(FWRetractMenu); + } +#endif + +//============================================================================= +// Mesh Bed Leveling +//============================================================================= + +#if HAS_MESH + + void ApplyMeshFadeHeight() { set_z_fade_height(planner.z_fade_height); } + void SetMeshFadeHeight() { SetPFloatOnClick(0, 100, 1, ApplyMeshFadeHeight); } + + void SetMeshActive() { + set_bed_leveling_enabled(!planner.leveling_active); + Draw_Chkb_Line(CurrentMenu->line(), planner.leveling_active); + DWIN_UpdateLCD(); } + + #if BOTH(HAS_HEATED_BED, PREHEAT_BEFORE_LEVELING) + void SetBedLevT() { SetPIntOnClick(MIN_BEDTEMP, MAX_BEDTEMP); } + #endif + + #if ENABLED(MESH_EDIT_MENU) + uint8_t mesh_x = 0, mesh_y = 0; + #define Z_OFFSET_MIN -3 + #define Z_OFFSET_MAX 3 + + void LiveEditMesh() { ((MenuItemPtrClass*)EditZValueItem)->value = &bedlevel.z_values[HMI_value.Select ? mesh_x : MenuData.Value][HMI_value.Select ? MenuData.Value : mesh_y]; EditZValueItem->redraw(); } + void ApplyEditMeshX() { mesh_x = MenuData.Value; } + void SetEditMeshX() { HMI_value.Select = 0; SetIntOnClick(0, GRID_MAX_POINTS_X - 1, mesh_x, ApplyEditMeshX, LiveEditMesh); } + void ApplyEditMeshY() { mesh_y = MenuData.Value; } + void SetEditMeshY() { HMI_value.Select = 1; SetIntOnClick(0, GRID_MAX_POINTS_Y - 1, mesh_y, ApplyEditMeshY, LiveEditMesh); } + void SetEditZValue() { SetPFloatOnClick(Z_OFFSET_MIN, Z_OFFSET_MAX, 3); } + #endif #endif +#if ENABLED(AUTO_BED_LEVELING_UBL) + + void ApplyUBLSlot() { bedlevel.storage_slot = MenuData.Value; } + void SetUBLSlot() { SetIntOnClick(0, settings.calc_num_meshes() - 1, bedlevel.storage_slot, ApplyUBLSlot); } + void onDrawUBLSlot(MenuItemClass* menuitem, int8_t line) { + if (bedlevel.storage_slot < 0) bedlevel.storage_slot = 0; + onDrawIntMenu(menuitem, line, bedlevel.storage_slot); + } + + void ApplyUBLTiltGrid() { ubl_tools.tilt_grid = MenuData.Value; } + void SetUBLTiltGrid() { SetIntOnClick(1, 3, ubl_tools.tilt_grid, ApplyUBLTiltGrid); } + + void UBLTiltMesh() { + if (bedlevel.storage_slot < 0) bedlevel.storage_slot = 0; + char buf[15]; + if (ubl_tools.tilt_grid > 1) { + sprintf_P(buf, PSTR("G28O\nG29 J%i"), ubl_tools.tilt_grid); + gcode.process_subcommands_now(buf); + } + else + gcode.process_subcommands_now(F("G28O\nG29J")); + LCD_MESSAGE(MSG_UBL_MESH_TILTED); + } + + void UBLSmartFillMesh() { + bedlevel.smart_fill_mesh(); + LCD_MESSAGE(MSG_UBL_MESH_FILLED); + } + + bool UBLValidMesh() { + const bool valid = ubl_tools.validate(); + if (!valid) bedlevel.invalidate(); + return valid; + } + + void UBLSaveMesh() { + if (bedlevel.storage_slot < 0) bedlevel.storage_slot = 0; + settings.store_mesh(bedlevel.storage_slot); + ui.status_printf(0, GET_TEXT_F(MSG_MESH_SAVED), bedlevel.storage_slot); + DONE_BUZZ(true); + } + + void UBLLoadMesh() { + if (bedlevel.storage_slot < 0) bedlevel.storage_slot = 0; + settings.load_mesh(bedlevel.storage_slot); + if (UBLValidMesh()) { + ui.status_printf(0, GET_TEXT_F(MSG_MESH_LOADED), bedlevel.storage_slot); + DONE_BUZZ(true); + } + else { + LCD_MESSAGE_F("Invalid Mesh Loaded"); + DONE_BUZZ(false); + } + } + +#endif // AUTO_BED_LEVELING_UBL + +#if HAS_MESH + void Draw_MeshSet_Menu() { + checkkey = Menu; + if (SetMenu(MeshMenu, GET_TEXT_F(MSG_MESH_LEVELING), 15)) { + BACK_ITEM(Draw_AdvancedSettings_Menu); + #if BOTH(HAS_HEATED_BED, PREHEAT_BEFORE_LEVELING) + EDIT_ITEM_F(ICON_Temperature, MSG_UBL_SET_TEMP_BED, onDrawPIntMenu, SetBedLevT, &HMI_data.BedLevT); + #endif + EDIT_ITEM_F(ICON_SetZOffset, MSG_Z_FADE_HEIGHT, onDrawPFloatMenu, SetMeshFadeHeight, &planner.z_fade_height); + EDIT_ITEM_F(ICON_UBLActive, MSG_ACTIVATE_MESH, onDrawChkbMenu, SetMeshActive, &planner.leveling_active); + #if HAS_BED_PROBE + MENU_ITEM_F(ICON_Level, MSG_AUTO_MESH, onDrawMenuItem, AutoLev); + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + EDIT_ITEM_F(ICON_UBLActive, MSG_UBL_STORAGE_SLOT, onDrawUBLSlot, SetUBLSlot, &bedlevel.storage_slot); + MENU_ITEM_F(ICON_UBLActive, MSG_UBL_SAVE_MESH, onDrawMenuItem, UBLSaveMesh); + MENU_ITEM_F(ICON_UBLActive, MSG_UBL_LOAD_MESH, onDrawMenuItem, UBLLoadMesh); + EDIT_ITEM_F(ICON_UBLActive, MSG_UBL_TILTING_GRID, onDrawPInt8Menu, SetUBLTiltGrid, &ubl_tools.tilt_grid); + MENU_ITEM_F(ICON_UBLActive, MSG_UBL_TILT_MESH, onDrawMenuItem, UBLTiltMesh); + MENU_ITEM_F(ICON_UBLActive, MSG_UBL_SMART_FILLIN, onDrawMenuItem, UBLSmartFillMesh); + #endif + #if ENABLED(MESH_EDIT_MENU) + MENU_ITEM_F(ICON_UBLActive, MSG_EDIT_MESH, onDrawSubMenu, Draw_EditMesh_Menu); + #endif + MENU_ITEM_F(ICON_MeshViewer, MSG_MESH_VIEW, onDrawSubMenu, DWIN_MeshViewer); + } + UpdateMenu(MeshMenu); + } + + #if ENABLED(MESH_EDIT_MENU) + void Draw_EditMesh_Menu() { + checkkey = Menu; + if (SetMenu(EditMeshMenu, GET_TEXT_F(MSG_EDIT_MESH), 4)) { + mesh_x = mesh_y = 0; + BACK_ITEM(Draw_MeshSet_Menu); + EDIT_ITEM_F(ICON_UBLActive, MSG_MESH_X, onDrawPInt8Menu, SetEditMeshX, &mesh_x); + EDIT_ITEM_F(ICON_UBLActive, MSG_MESH_Y, onDrawPInt8Menu, SetEditMeshY, &mesh_y); + EditZValueItem = EDIT_ITEM_F(ICON_UBLActive, MSG_MESH_EDIT_Z, onDrawPFloat3Menu, SetEditZValue, &bedlevel.z_values[mesh_x][mesh_y]); + } + UpdateMenu(EditMeshMenu); + } + #endif + +#endif // HAS_MESH + #endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index b61ed846dfcb..4f992b3a7895 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -24,8 +24,8 @@ /** * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.15.2 - * Date: 2022/03/01 + * Version: 3.17.2 + * Date: 2022/04/08 */ #include "dwin_defines.h" @@ -73,12 +73,13 @@ enum pidresult_t : uint8_t { typedef struct { int8_t Color[3]; // Color components pidresult_t pidresult = PID_DONE; - int8_t Preheat = 0; // Material Select 0: PLA, 1: ABS, 2: Custom + uint8_t Select = 0; // Auxiliary selector variable AxisEnum axis = X_AXIS; // Axis Select } HMI_value_t; typedef struct { uint8_t language; + bool percent_flag:1; // percent was override by M73 bool remain_flag:1; // remain was override by M73 bool pause_flag:1; // printing is paused bool pause_action:1; // flag a pause action @@ -103,9 +104,53 @@ extern millis_t dwin_heat_time; void Popup_PowerLossRecovery(); #endif -// SD Card -void HMI_SDCardInit(); -void HMI_SDCardUpdate(); +// Tool Functions +#if ENABLED(EEPROM_SETTINGS) + void WriteEeprom(); + void ReadEeprom(); + void ResetEeprom(); + #if HAS_MESH + void SaveMesh(); + #endif +#endif +void RebootPrinter(); +void DisableMotors(); +void AutoLev(); +void AutoHome(); +#if HAS_PREHEAT + void DoPreheat0(); + void DoPreheat1(); + void DoPreheat2(); +#endif +void DoCoolDown(); +#if HAS_HOTEND + void HotendPID(); +#endif +#if HAS_HEATED_BED + void BedPID(); +#endif +#if ENABLED(BAUD_RATE_GCODE) + void HMI_SetBaudRate(); + void SetBaud115K(); + void SetBaud250K(); +#endif +#if HAS_LCD_BRIGHTNESS + void TurnOffBacklight(); +#endif +void ApplyExtMinT(); +void ParkHead(); +#if HAS_ONESTEP_LEVELING + void Trammingwizard(); +#endif +#if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + void ApplyLEDColor(); +#endif +#if ENABLED(AUTO_BED_LEVELING_UBL) + void UBLTiltMesh(); + bool UBLValidMesh(); + void UBLSaveMesh(); + void UBLLoadMesh(); +#endif // Other void Goto_PrintProcess(); @@ -114,29 +159,19 @@ void Goto_Info_Menu(); void Goto_PowerLossRecovery(); void Goto_ConfirmToPrint(); void DWIN_Draw_Dashboard(const bool with_update); // Status Area -void Draw_Main_Area(); // Redraw main area; -void DWIN_Redraw_screen(); // Redraw all screen elements +void Draw_Main_Area(); // Redraw main area +void DWIN_DrawStatusLine(const char *text); // Draw simple status text +void DWIN_DrawStatusLine(FSTR_P fstr); +void DWIN_RedrawDash(); // Redraw Dash and Status line +void DWIN_RedrawScreen(); // Redraw all screen elements void HMI_MainMenu(); // Main process screen void HMI_SelectFile(); // File page void HMI_Printing(); // Print page void HMI_ReturnScreen(); // Return to previous screen before popups -void ApplyExtMinT(); -void HMI_SetLanguageCache(); // Set the languaje image cache -void RebootPrinter(); -#if ENABLED(BAUD_RATE_GCODE) - void HMI_SetBaudRate(); - void SetBaud115K(); - void SetBaud250K(); -#endif -#if ENABLED(EEPROM_SETTINGS) - void WriteEeprom(); - void ReadEeprom(); - void ResetEeprom(); -#endif - void HMI_WaitForUser(); void HMI_SaveProcessID(const uint8_t id); -void HMI_AudioFeedback(const bool success=true); +void HMI_SDCardInit(); +void HMI_SDCardUpdate(); void EachMomentUpdate(); void update_variable(); void DWIN_InitScreen(); @@ -158,12 +193,12 @@ void DWIN_Print_Aborted(); #if HAS_FILAMENT_SENSOR void DWIN_FilamentRunout(const uint8_t extruder); #endif -void DWIN_Progress_Update(); +void DWIN_M73(); void DWIN_Print_Header(const char *text); void DWIN_SetColorDefaults(); void DWIN_ApplyColor(); -void DWIN_StoreSettings(char *buff); -void DWIN_LoadSettings(const char *buff); +void DWIN_CopySettingsTo(char * const buff); +void DWIN_CopySettingsFrom(const char * const buff); void DWIN_SetDataDefaults(); void DWIN_RebootScreen(); @@ -203,9 +238,7 @@ void Draw_Tramming_Menu(); #if HAS_BED_PROBE void Draw_ProbeSet_Menu(); #endif -#if HAS_FILAMENT_SENSOR - void Draw_FilSet_Menu(); -#endif +void Draw_FilSet_Menu(); #if ENABLED(NOZZLE_PARK_FEATURE) void Draw_ParkPos_Menu(); #endif @@ -248,3 +281,12 @@ void Draw_Steps_Menu(); #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) void Draw_Homing_Menu(); #endif +#if ENABLED(FWRETRACT) + void Draw_FWRetract_Menu(); +#endif +#if HAS_MESH + void Draw_MeshSet_Menu(); + #if ENABLED(MESH_EDIT_MENU) + void Draw_EditMesh_Menu(); + #endif +#endif diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 4ebc2c16c6e4..1517acd238d0 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -34,23 +34,11 @@ #include "../../../inc/MarlinConfigPre.h" #include -#if DISABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) - #error "INDIVIDUAL_AXIS_HOMING_SUBMENU is required with ProUI." -#endif -#if DISABLED(LCD_SET_PROGRESS_MANUALLY) - #error "LCD_SET_PROGRESS_MANUALLY is required with ProUI." -#endif -#if DISABLED(STATUS_MESSAGE_SCROLLING) - #error "STATUS_MESSAGE_SCROLLING is required with ProUI." -#endif -#if DISABLED(BAUD_RATE_GCODE) - #error "BAUD_RATE_GCODE is required with ProUI." -#endif -#if DISABLED(SOUND_MENU_ITEM) - #error "SOUND_MENU_ITEM is required with ProUI." -#endif -#if DISABLED(PRINTCOUNTER) - #error "PRINTCOUNTER is required with ProUI." +#define HAS_ESDIAG 1 +#define HAS_PIDPLOT 1 +#define HAS_GCODE_PREVIEW 1 +#if defined(__STM32F1__) || defined(STM32F1) + #define DASH_REDRAW 1 #endif #include "../common/dwin_color.h" @@ -80,8 +68,8 @@ #define HAS_ESDIAG 1 -#if ENABLED(LED_CONTROL_MENU, HAS_COLOR_LEDS) - #define Def_Leds_Color LEDColorWhite() +#if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + #define Def_Leds_Color 0xFFFFFFFF #endif #if ENABLED(CASELIGHT_USES_BRIGHTNESS) #define Def_CaseLight_Brightness 255 @@ -128,14 +116,13 @@ typedef struct { #endif bool FullManualTramming = false; // Led - #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) - LEDColor Led_Color = Def_Leds_Color; + #if ENABLED(MESH_BED_LEVELING) + float ManualZOffset = 0; #endif - // Case Light - #if ENABLED(CASELIGHT_USES_BRIGHTNESS) - uint8_t CaseLight_Brightness = Def_CaseLight_Brightness; + #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + uint32_t LED_Color = Def_Leds_Color; #endif } HMI_data_t; -static constexpr size_t eeprom_data_size = 64; +static constexpr size_t eeprom_data_size = sizeof(HMI_data_t); extern HMI_data_t HMI_data; diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp index 3da3fc808624..6cdafc8a935f 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp @@ -23,8 +23,8 @@ /** * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.9.1 - * Date: 2022/02/08 + * Version: 3.10.1 + * Date: 2022/03/06 */ #include "../../../inc/MarlinConfigPre.h" @@ -35,54 +35,6 @@ #include "dwin_lcd.h" -/*---------------------------------------- Numeric related functions ----------------------------------------*/ - -// Draw a numeric value -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// signedMode: 1=signed; 0=unsigned -// 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 -// fNum: Number of decimal digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_Value(uint8_t bShow, bool signedMode, 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, int32_t value) { - size_t i = 0; - DWIN_Byte(i, 0x14); - // Bit 7: bshow - // Bit 6: 1 = signed; 0 = unsigned number; - // Bit 5: zeroFill - // Bit 4: zeroMode - // Bit 3-0: size - DWIN_Byte(i, (bShow * 0x80) | (signedMode * 0x40) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, signedMode && (value >= 0) ? iNum + 1 : iNum); - DWIN_Byte(i, fNum); - DWIN_Word(i, x); - DWIN_Word(i, y); - // Write a big-endian 64 bit integer - const size_t p = i + 1; - for (size_t count = 8; count--;) { // 7..0 - ++i; - DWIN_SendBuf[p + count] = value; - value >>= 8; - } - DWIN_Send(i); -} - -// Draw a numeric value -// value: positive unscaled float value -void DWIN_Draw_Value(uint8_t bShow, bool signedMode, 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, float value) { - const int32_t val = round(value * POW(10, fNum)); - DWIN_Draw_Value(bShow, signedMode, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, val); -} - /*---------------------------------------- Picture related functions ----------------------------------------*/ // Display QR code @@ -195,7 +147,7 @@ void DWIN_SRAMToPic(uint8_t picID) { //--------------------------Test area ------------------------- -//void DWIN_ReadSRAM(uint16_t addr, uint8_t length, const char * const data) { +//void DWIN_ReadSRAM(uint16_t addr, const uint8_t length, const char * const data) { // size_t i = 0; // DWIN_Byte(i, 0x32); // DWIN_Byte(i, 0x5A); // 0x5A Read from SRAM - 0xA5 Read from Flash diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.h b/Marlin/src/lcd/e3v2/proui/dwin_lcd.h index cdffb96f2f30..6e0a254db4ee 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.h @@ -24,30 +24,12 @@ /** * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.9.1 - * Date: 2022/02/08 + * Version: 3.10.1 + * Date: 2022/03/06 */ #include "../common/dwin_api.h" -// Draw a numeric value -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// signedMode: 1=signed; 0=unsigned -// 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 -// fNum: Number of decimal digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_Value(uint8_t bShow, bool signedMode, 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, int32_t value); -// value: positive unscaled float value -void DWIN_Draw_Value(uint8_t bShow, bool signedMode, 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, float value); - // Display QR code // The size of the QR code is (46*QR_Pixel)*(46*QR_Pixel) dot matrix // QR_Pixel: The pixel size occupied by each point of the QR code: 0x01-0x0F (1-16) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.h b/Marlin/src/lcd/e3v2/proui/dwin_popup.h index 0d864994754b..b4503ea7866b 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.h @@ -50,7 +50,7 @@ inline void Draw_Popup_Bkgd() { template void DWIN_Draw_Popup(const uint8_t icon, T amsg1=nullptr, U amsg2=nullptr, uint8_t button=0) { - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); Draw_Popup_Bkgd(); if (icon) DWINUI::Draw_Icon(icon, 101, 105); if (amsg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, amsg1); diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.cpp b/Marlin/src/lcd/e3v2/proui/dwinui.cpp index ddc494fc8492..ecb4754a0f35 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwinui.cpp @@ -23,8 +23,8 @@ /** * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.15.1 - * Date: 2022/02/25 + * Version: 3.17.1 + * Date: 2022/04/12 */ #include "../../../inc/MarlinConfigPre.h" @@ -39,12 +39,6 @@ //#define DEBUG_OUT 1 #include "../../../core/debug_out.h" -int8_t MenuItemTotal = 0; -int8_t MenuItemCount = 0; -MenuItemClass** MenuItems = nullptr; -MenuClass *CurrentMenu = nullptr; -MenuClass *PreviousMenu = nullptr; - xy_int_t DWINUI::cursor = { 0 }; uint16_t DWINUI::pencolor = Color_White; uint16_t DWINUI::textcolor = Def_Text_Color; @@ -53,16 +47,15 @@ uint16_t DWINUI::buttoncolor = Def_Button_Color; uint8_t DWINUI::font = font8x16; FSTR_P const DWINUI::Author = F(STRING_CONFIG_H_AUTHOR); -void (*DWINUI::onCursorErase)(const int8_t line)=nullptr; -void (*DWINUI::onCursorDraw)(const int8_t line)=nullptr; -void (*DWINUI::onTitleDraw)(TitleClass* title)=nullptr; -void (*DWINUI::onMenuDraw)(MenuClass* menu)=nullptr; +void (*DWINUI::onTitleDraw)(TitleClass* title) = nullptr; void DWINUI::init() { - TERN_(DEBUG_DWIN, SERIAL_ECHOPGM("\r\nDWIN handshake ")); delay(750); // Delay for wait to wakeup screen - const bool hs = DWIN_Handshake(); - TERN(DEBUG_DWIN, SERIAL_ECHOLNF(hs ? F("ok.") : F("error.")), UNUSED(hs)); + const bool hs = DWIN_Handshake(); UNUSED(hs); + #if ENABLED(DEBUG_DWIN) + SERIAL_ECHOPGM("DWIN_Handshake "); + SERIAL_ECHOLNF(hs ? F("ok.") : F("error.")); + #endif DWIN_Frame_SetDir(1); cursor.reset(); pencolor = Color_White; @@ -164,16 +157,19 @@ void DWINUI::Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint1 DWIN_Draw_String(bShow, size, color, bColor, x, y, string); } -// // Draw a Centered string using DWIN_WIDTH -// void DWINUI::Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string) { -// const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(string) * fontWidth(size)) / 2 - 1; -// DWIN_Draw_String(bShow, size, color, bColor, x, y, string); -// } +// Draw a char +// color: Character color +// x: abscissa of the display +// y: ordinate of the display +// c: ASCII code of char +void DWINUI::Draw_Char(uint16_t color, uint16_t x, uint16_t y, const char c) { + const char string[2] = { c, 0}; + DWIN_Draw_String(false, font, color, backcolor, x, y, string, 1); +} -// Draw a char at cursor position +// Draw a char at cursor position and increment cursor void DWINUI::Draw_Char(uint16_t color, const char c) { - const char string[2] = { c, 0}; - DWIN_Draw_String(false, font, color, backcolor, cursor.x, cursor.y, string, 1); + Draw_Char(color, cursor.x, cursor.y, c); MoveBy(fontWidth(font), 0); } @@ -190,6 +186,36 @@ void DWINUI::Draw_String(uint16_t color, const char * const string, uint16_t rli MoveBy(strlen(string) * fontWidth(font), 0); } +// Draw a numeric integer value +// bShow: true=display background color; false=don't display background color +// signedMode: 1=signed; 0=unsigned +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWINUI::Draw_Int(uint8_t bShow, bool signedMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, int32_t value) { + char nstr[10]; + sprintf_P(nstr, PSTR("%*li"), (signedMode ? iNum + 1 : iNum), value); + DWIN_Draw_String(bShow, size, color, bColor, x, y, nstr); +} + +// Draw a numeric float value +// bShow: true=display background color; false=don't display background color +// signedMode: 1=signed; 0=unsigned +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// fNum: Number of decimal digits +// x/y: Upper-left coordinate +// value: float value +void DWINUI::Draw_Float(uint8_t bShow, bool signedMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { + char nstr[10]; + DWIN_Draw_String(bShow, size, color, bColor, x, y, dtostrf(value, iNum + (signedMode ? 2:1) + fNum, fNum, nstr)); +} + // ------------------------- Buttons ------------------------------// void DWINUI::Draw_Button(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, const char * const caption) { @@ -204,6 +230,7 @@ void DWINUI::Draw_Button(uint8_t id, uint16_t x, uint16_t y) { case BTN_Continue: Draw_Button(GET_TEXT_F(MSG_BUTTON_CONTINUE), x, y); break; case BTN_Print : Draw_Button(GET_TEXT_F(MSG_BUTTON_PRINT), x, y); break; case BTN_Save : Draw_Button(GET_TEXT_F(MSG_BUTTON_SAVE), x, y); break; + case BTN_Purge : Draw_Button(GET_TEXT_F(MSG_BUTTON_PURGE), x, y); break; default: break; } } @@ -265,7 +292,7 @@ uint16_t DWINUI::ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t colo return RGB(R, G, B); } -// Color Interpolator through Red->Yellow->Green->Blue +// Color Interpolator through Red->Yellow->Green->Blue (Pro UI) // val : Interpolator minv..maxv // minv : Minimum value // maxv : Maximum value @@ -304,37 +331,10 @@ void DWINUI::Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t } // Clear Menu by filling the menu area with background color -void DWINUI::ClearMenuArea() { +void DWINUI::ClearMainArea() { DWIN_Draw_Rectangle(1, backcolor, 0, TITLE_HEIGHT, DWIN_WIDTH - 1, STATUS_Y - 1); } -void DWINUI::MenuItemsClear() { - if (MenuItems == nullptr) return; - for (int8_t i = 0; i < MenuItemCount; i++) delete MenuItems[i]; - delete[] MenuItems; - MenuItems = nullptr; - MenuItemCount = 0; - MenuItemTotal = 0; -} - -void DWINUI::MenuItemsPrepare(int8_t totalitems) { - MenuItemsClear(); - MenuItemTotal = totalitems; - MenuItems = new MenuItemClass*[totalitems]; -} - -MenuItemClass* DWINUI::MenuItemsAdd(MenuItemClass* menuitem) { - if (MenuItemCount < MenuItemTotal) { - MenuItems[MenuItemCount] = menuitem; - menuitem->pos = MenuItemCount++; - return menuitem; - } - else { - delete menuitem; - return nullptr; - } -} - /* Title Class ==============================================================*/ TitleClass Title; @@ -375,85 +375,4 @@ void TitleClass::FrameCopy(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { FrameCopy(1, x, y, x + w - 1, y + h - 1); } -/* Menu Class ===============================================================*/ - -MenuClass::MenuClass() { - selected = 0; - topline = 0; -} - -void MenuClass::draw() { - MenuTitle.draw(); - if (DWINUI::onMenuDraw != nullptr) (*DWINUI::onMenuDraw)(this); - for (int8_t i = 0; i < MenuItemCount; i++) - MenuItems[i]->draw(i - topline); - if (DWINUI::onCursorDraw != nullptr) DWINUI::onCursorDraw(line()); - DWIN_UpdateLCD(); -} - -void MenuClass::onScroll(bool dir) { - int8_t sel = selected; - if (dir) sel++; else sel--; - LIMIT(sel, 0, MenuItemCount - 1); - if (sel != selected) { - if (DWINUI::onCursorErase != nullptr) DWINUI::onCursorErase(line()); - if ((sel - topline) == TROWS) { - DWIN_Frame_AreaMove(1, DWIN_SCROLL_UP, MLINE, DWINUI::backcolor, 0, TITLE_HEIGHT + 1, DWIN_WIDTH, STATUS_Y - 1); - topline++; - MenuItems[sel]->draw(TROWS - 1); - } - if ((sel < topline)) { - DWIN_Frame_AreaMove(1, DWIN_SCROLL_DOWN, MLINE, DWINUI::backcolor, 0, TITLE_HEIGHT + 1, DWIN_WIDTH, STATUS_Y - 1); - topline--; - MenuItems[sel]->draw(0); - } - selected = sel; - if (DWINUI::onCursorDraw != nullptr) DWINUI::onCursorDraw(line()); - DWIN_UpdateLCD(); - } -} - -void MenuClass::onClick() { - if (MenuItems[selected]->onClick != nullptr) (*MenuItems[selected]->onClick)(); -} - -MenuItemClass *MenuClass::SelectedItem() { - return MenuItems[selected]; -} - -/* MenuItem Class ===========================================================*/ - -MenuItemClass::MenuItemClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)()) { - icon = cicon; - onClick = onclick; - onDraw = ondraw; - const uint8_t len = _MIN(sizeof(caption) - 1, strlen(text)); - memcpy(&caption[0], text, len); - caption[len] = '\0'; -} - -MenuItemClass::MenuItemClass(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)()) { - icon = cicon; - onClick = onclick; - onDraw = ondraw; - caption[0] = '\0'; - frameid = id; - frame = { x1, y1, x2, y2 }; -} - -void MenuItemClass::SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { - caption[0] = '\0'; - frameid = id; - frame = { x1, y1, x2, y2 }; -} - -void MenuItemClass::draw(int8_t line) { - if (line < 0 || line >= TROWS) return; - if (onDraw != nullptr) (*onDraw)(this, line); -}; - -MenuItemPtrClass::MenuItemPtrClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) : MenuItemClass(cicon, text, ondraw, onclick) { - value = val; -}; - #endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h index 1504dcd30598..f8ff0917694d 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.h +++ b/Marlin/src/lcd/e3v2/proui/dwinui.h @@ -24,8 +24,8 @@ /** * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.15.1 - * Date: 2022/02/25 + * Version: 3.17.1 + * Date: 2022/04/12 */ #include "dwin_lcd.h" @@ -37,6 +37,7 @@ #define ICON_AdvSet ICON_Language #define ICON_BedSizeX ICON_PrintSize #define ICON_BedSizeY ICON_PrintSize +#define ICON_BedTramming ICON_SetHome #define ICON_Binary ICON_Contact #define ICON_Brightness ICON_Motion #define ICON_Cancel ICON_StockConfiguration @@ -50,10 +51,12 @@ #define ICON_FilUnload ICON_ReadEEPROM #define ICON_Flow ICON_StepE #define ICON_Folder ICON_More +#define ICON_FWRetract ICON_StepE #define ICON_FWRetLength ICON_StepE #define ICON_FWRetSpeed ICON_Setspeed #define ICON_FWRetZRaise ICON_MoveZ #define ICON_FWRecSpeed ICON_Setspeed +#define ICON_FWRecExtra ICON_StepE #define ICON_HomeX ICON_MoveX #define ICON_HomeY ICON_MoveY #define ICON_HomeZ ICON_MoveZ @@ -102,6 +105,9 @@ #define ICON_SetBaudRate ICON_Setspeed #define ICON_SetCustomPreheat ICON_SetEndTemp #define ICON_Sound ICON_Cool +#define ICON_TBSetup ICON_Contact +#define ICON_UBLActive ICON_HotendTemp + #define ICON_CaseLight ICON_Motion #define ICON_LedControl ICON_Motion @@ -111,12 +117,27 @@ #define BTN_Confirm 89 #define BTN_Print 90 #define BTN_Save 91 +#define BTN_Purge 92 // Extended and default UI Colors #define Color_Black 0 #define Color_Green RGB(0,63,0) #define Color_Aqua RGB(0,63,31) #define Color_Blue RGB(0,0,31) +#define Color_Light_White 0xBDD7 +#define Color_Light_Green 0x3460 +#define Color_Cyan 0x07FF +#define Color_Light_Cyan 0x04F3 +#define Color_Light_Blue 0x3A6A +#define Color_Magenta 0xF81F +#define Color_Light_Magenta 0x9813 +#define Color_Light_Red 0x8800 +#define Color_Orange 0xFA20 +#define Color_Light_Orange 0xFBC0 +#define Color_Light_Yellow 0x8BE0 +#define Color_Brown 0xCC27 +#define Color_Light_Brown 0x6204 +#define Color_Grey 0x18E3 // UI element defines and constants #define DWIN_FONT_MENU font8x16 @@ -130,7 +151,7 @@ #define UNITFDIGITS 1 #define MINUNITMULT POW(10, UNITFDIGITS) -constexpr uint16_t TITLE_HEIGHT = 30, // Title bar height +constexpr uint8_t TITLE_HEIGHT = 30, // Title bar height MLINE = 53, // Menu line height TROWS = (STATUS_Y - TITLE_HEIGHT) / MLINE, // Total rows MROWS = TROWS - 1, // Other-than-Back @@ -149,10 +170,6 @@ constexpr uint16_t TITLE_HEIGHT = 30, // Title bar heig // Menuitem caption Y position #define MBASE(L) (MYPOS(L) + CAPOFF) -// Create and add a MenuItem object to the menu array -#define MENU_ITEM(V...) DWINUI::MenuItemsAdd(new MenuItemClass(V)) -#define EDIT_ITEM(V...) DWINUI::MenuItemsAdd(new MenuItemPtrClass(V)) - typedef struct { uint16_t left, top, right, bottom; } rect_t; typedef struct { uint16_t x, y, w, h; } frame_rect_t; @@ -173,49 +190,6 @@ class TitleClass { }; extern TitleClass Title; -class MenuItemClass { -protected: -public: - int8_t pos = 0; - uint8_t icon = 0; - char caption[32] = ""; - uint8_t frameid = 0; - rect_t frame = {0}; - void (*onDraw)(MenuItemClass* menuitem, int8_t line) = nullptr; - void (*onClick)() = nullptr; - MenuItemClass() {}; - MenuItemClass(uint8_t cicon, const char * const text=nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); - MenuItemClass(uint8_t cicon, FSTR_P text = nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr) : MenuItemClass(cicon, FTOP(text), ondraw, onclick){} - MenuItemClass(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); - void SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); - virtual ~MenuItemClass(){}; - virtual void draw(int8_t line); -}; - -class MenuItemPtrClass: public MenuItemClass { -public: - void *value = nullptr; - using MenuItemClass::MenuItemClass; - MenuItemPtrClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val); - MenuItemPtrClass(uint8_t cicon, FSTR_P text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) : MenuItemPtrClass(cicon, FTOP(text), ondraw, onclick, val){} -}; - -class MenuClass { -public: - int8_t topline = 0; - int8_t selected = 0; - TitleClass MenuTitle; - MenuClass(); - virtual ~MenuClass(){}; - inline int8_t line() { return selected - topline; }; - inline int8_t line(uint8_t pos) {return pos - topline; }; - void draw(); - void onScroll(bool dir); - void onClick(); - MenuItemClass* SelectedItem(); -}; -extern MenuClass *CurrentMenu; - namespace DWINUI { extern xy_int_t cursor; extern uint16_t pencolor; @@ -225,10 +199,7 @@ namespace DWINUI { extern uint8_t font; extern FSTR_P const Author; - extern void (*onCursorErase)(const int8_t line); - extern void (*onCursorDraw)(const int8_t line); extern void (*onTitleDraw)(TitleClass* title); - extern void (*onMenuDraw)(MenuClass* menu); // DWIN LCD Initialization void init(); @@ -304,129 +275,121 @@ namespace DWINUI { DWIN_ICON_Show(true, false, false, ICON, icon, x, y); } - // Draw a positive integer + // Draw a numeric integer value // 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 + // signedMode: 1=signed; 0=unsigned // size: Font size // color: Character color // bColor: Background color // iNum: Number of digits // x/y: Upper-left coordinate // value: Integer value - inline void Draw_Int(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, long value) { - DWIN_Draw_Value(bShow, 0, zeroFill, zeroMode, size, color, bColor, iNum, 0, x, y, value); + void Draw_Int(uint8_t bShow, bool signedMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, int32_t value); + + // Draw a positive integer + inline void Draw_Int(uint8_t bShow, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { + Draw_Int(bShow, 0, size, color, bColor, iNum, x, y, value); } inline void Draw_Int(uint8_t iNum, long value) { - DWIN_Draw_Value(false, 0, true, 0, font, textcolor, backcolor, iNum, 0, cursor.x, cursor.y, value); + Draw_Int(false, 0, font, textcolor, backcolor, iNum, cursor.x, cursor.y, value); MoveBy(iNum * fontWidth(font), 0); } inline void Draw_Int(uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_Value(false, 0, true, 0, font, textcolor, backcolor, iNum, 0, x, y, value); + Draw_Int(false, 0, font, textcolor, backcolor, iNum, x, y, value); } inline void Draw_Int(uint16_t color, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_Value(false, 0, true, 0, font, color, backcolor, iNum, 0, x, y, value); + Draw_Int(false, 0, font, color, backcolor, iNum, x, y, value); } inline void Draw_Int(uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_Value(true, 0, true, 0, font, color, bColor, iNum, 0, x, y, value); + Draw_Int(true, 0, font, color, bColor, iNum, x, y, value); } inline void Draw_Int(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_Value(true, 0, true, 0, size, color, bColor, iNum, 0, x, y, value); + Draw_Int(true, 0, size, color, bColor, iNum, x, y, value); } // Draw a signed 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 - inline void Draw_Signed_Int(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, long value) { - DWIN_Draw_Value(bShow, 1, zeroFill, zeroMode, size, color, bColor, iNum, 0, x, y, value); + inline void Draw_Signed_Int(uint8_t bShow, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { + Draw_Int(bShow, 1, size, color, bColor, iNum, x, y, value); } inline void Draw_Signed_Int(uint8_t iNum, long value) { - DWIN_Draw_Value(false, 1, true, 0, font, textcolor, backcolor, iNum, 0, cursor.x, cursor.y, value); + Draw_Int(false, 1, font, textcolor, backcolor, iNum, cursor.x, cursor.y, value); MoveBy(iNum * fontWidth(font), 0); } inline void Draw_Signed_Int(uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_Value(false, 1, true, 0, font, textcolor, backcolor, iNum, 0, x, y, value); + Draw_Int(false, 1, font, textcolor, backcolor, iNum, x, y, value); } inline void Draw_Signed_Int(uint16_t color, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_Value(false, 1, true, 0, font, color, backcolor, iNum, 0, x, y, value); + Draw_Int(false, 1, font, color, backcolor, iNum, x, y, value); } inline void Draw_Signed_Int(uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_Value(true, 1, true, 0, font, color, bColor, iNum, 0, x, y, value); + Draw_Int(true, 1, font, color, bColor, iNum, x, y, value); } inline void Draw_Signed_Int(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_Value(true, 1, true, 0, size, color, bColor, iNum, 0, x, y, value); + Draw_Int(true, 1, size, color, bColor, iNum, x, y, value); } - // Draw a positive floating point number + // Draw a numeric float value // 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 + // signedMode: 1=signed; 0=unsigned // size: Font size // color: Character color // bColor: Background color - // iNum: Number of whole digits + // iNum: Number of digits // fNum: Number of decimal digits - // x/y: Upper-left point - // value: Float value - inline void Draw_Float(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, float value) { - DWIN_Draw_Value(bShow, 0, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); + // x/y: Upper-left coordinate + // value: float value + void Draw_Float(uint8_t bShow, bool signedMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value); + + // Draw a positive floating point number + inline void Draw_Float(uint8_t bShow, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { + Draw_Float(bShow, 0, size, color, bColor, iNum, fNum, x, y, value); } inline void Draw_Float(uint8_t iNum, uint8_t fNum, float value) { - DWIN_Draw_Value(false, 0, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); + Draw_Float(false, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); MoveBy((iNum + fNum + 1) * fontWidth(font), 0); } inline void Draw_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_Value(false, 0, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); + Draw_Float(false, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); } - inline void Draw_Float(uint16_t color, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_Value(false, 0, true, 0, font, color, backcolor, iNum, fNum, x, y, value); + inline void Draw_Float(uint8_t size, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { + Draw_Float(false, 0, size, textcolor, backcolor, iNum, fNum, x, y, value); } inline void Draw_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_Value(true, 0, true, 0, font, color, bColor, iNum, fNum, x, y, value); + Draw_Float(true, 0, font, color, bColor, iNum, fNum, x, y, value); } inline void Draw_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_Value(true, 0, true, 0, size, color, bColor, iNum, fNum, x, y, value); + Draw_Float(true, 0, size, color, bColor, iNum, fNum, x, y, value); } // Draw a signed 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 - inline void Draw_Signed_Float(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, float value) { - DWIN_Draw_Value(bShow, 1, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); + inline void Draw_Signed_Float(uint8_t bShow, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { + Draw_Float(bShow, 1, size, color, bColor, iNum, fNum, x, y, value); } inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, float value) { - DWIN_Draw_Value(false, 1, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); + Draw_Float(false, 1, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); MoveBy((iNum + fNum + 1) * fontWidth(font), 0); } inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_Value(false, 1, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); + Draw_Float(false, 1, font, textcolor, backcolor, iNum, fNum, x, y, value); } inline void Draw_Signed_Float(uint8_t size, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_Value(false, 1, true, 0, size, textcolor, backcolor, iNum, fNum, x, y, value); + Draw_Float(false, 1, size, textcolor, backcolor, iNum, fNum, x, y, value); } inline void Draw_Signed_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_Value(true, 1, true, 0, font, color, bColor, iNum, fNum, x, y, value); + Draw_Float(true, 1, font, color, bColor, iNum, fNum, x, y, value); } inline void Draw_Signed_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_Value(true, 1, true, 0, size, color, bColor, iNum, fNum, x, y, value); + Draw_Float(true, 1, size, color, bColor, iNum, fNum, x, y, value); } - // Draw a char at cursor position + // Draw a char + // color: Character color + // x: abscissa of the display + // y: ordinate of the display + // c: ASCII code of char + void Draw_Char(uint16_t color, uint16_t x, uint16_t y, const char c); + inline void Draw_Char(uint16_t x, uint16_t y, const char c) { Draw_Char(textcolor, x, y, c); }; + // Draw a char at cursor position and increment cursor void Draw_Char(uint16_t color, const char c); inline void Draw_Char(const char c) { Draw_Char(textcolor, c); } @@ -591,17 +554,8 @@ namespace DWINUI { DWIN_WriteToMem(0xA5, addr, length, data); } - // Clear Menu by filling the area with background color + // Clear by filling the area with background color // Area (0, TITLE_HEIGHT, DWIN_WIDTH, STATUS_Y - 1) - void ClearMenuArea(); - - // Clear MenuItems array and free MenuItems elements - void MenuItemsClear(); - - // Prepare MenuItems array - void MenuItemsPrepare(int8_t totalitems); - - // Add elements to the MenuItems array - MenuItemClass* MenuItemsAdd(MenuItemClass* menuitem); + void ClearMainArea(); }; diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp index 0b450bd4c0f6..19d726037ce9 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp @@ -71,7 +71,7 @@ void draw_es_state(const bool is_hit) { void ESDiagClass::Draw() { Title.ShowCaption(F("End-stops Diagnostic")); - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); Draw_Popup_Bkgd(); DWINUI::Draw_Button(BTN_Continue, 86, 250); DWINUI::cursor.y = 80; diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp new file mode 100644 index 000000000000..adb23a96646b --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -0,0 +1,258 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 g-code thumbnail preview + * Author: Miguel A. Risco-Castillo + * version: 2.1 + * Date: 2021/06/19 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as + * published by the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see . + * + * For commercial applications additional licenses can be requested + */ + +#include "../../../inc/MarlinConfigPre.h" +#if ENABLED(DWIN_LCD_PROUI) + +#include "dwin_defines.h" + +#if HAS_GCODE_PREVIEW + +#include "../../../core/types.h" +#include "../../marlinui.h" +#include "../../../sd/cardreader.h" +#include "../../../MarlinCore.h" // for wait_for_user +#include "dwin_lcd.h" +#include "dwinui.h" +#include "dwin.h" +#include "dwin_popup.h" +#include "base64.hpp" +#include "gcode_preview.h" + +typedef struct { + char name[13] = ""; //8.3 + null + uint32_t thumbstart = 0; + int thumbsize = 0; + int thumbheight = 0; + int thumbwidth = 0; + uint8_t *thumbdata = nullptr; + float time = 0; + float filament = 0; + float layer = 0; + float width = 0; + float height = 0; + float length = 0; + void setname(const char * const fn); + void clear(); +} fileprop_t; +fileprop_t fileprop; + +void fileprop_t::setname(const char * const fn) { + const uint8_t len = _MIN(sizeof(name) - 1, strlen(fn)); + memcpy(&name[0], fn, len); + name[len] = '\0'; +} + +void fileprop_t::clear() { + fileprop.name[0] = '\0'; + fileprop.thumbstart = 0; + fileprop.thumbsize = 0; + fileprop.thumbheight = 0; + fileprop.thumbwidth = 0; + fileprop.thumbdata = nullptr; + fileprop.time = 0; + fileprop.filament = 0; + fileprop.layer = 0; + fileprop.height = 0; + fileprop.width = 0; + fileprop.length = 0; +} + +void Get_Value(char *buf, const char * const key, float &value) { + char num[10] = ""; + char * posptr = 0; + uint8_t i = 0; + if (!!value) return; + posptr = strstr(buf, key); + if (posptr != nullptr) { + while (i < sizeof(num)) { + char c = posptr[0]; + if (!ISEOL(c) && (c != 0)) { + if ((c > 47 && c < 58) || (c == '.')) num[i++] = c; + posptr++; + } + else { + num[i] = '\0'; + value = atof(num); + return; + } + } + } +} + +bool Has_Preview() { + const char * tbstart = "; thumbnail begin 230x180"; + char * posptr = 0; + uint8_t nbyte = 1; + uint32_t indx = 0; + char buf[256]; + float tmp = 0; + + fileprop.clear(); + fileprop.setname(card.filename); + + card.openFileRead(fileprop.name); + + while ((nbyte > 0) && (indx < 4 * sizeof(buf)) && !fileprop.thumbstart) { + nbyte = card.read(buf, sizeof(buf) - 1); + if (nbyte > 0) { + buf[nbyte] = '\0'; + Get_Value(buf, ";TIME:", fileprop.time); + Get_Value(buf, ";Filament used:", fileprop.filament); + Get_Value(buf, ";Layer height:", fileprop.layer); + Get_Value(buf, ";MINX:", tmp); + Get_Value(buf, ";MAXX:", fileprop.width); + fileprop.width -= tmp; + tmp = 0; + Get_Value(buf, ";MINY:", tmp); + Get_Value(buf, ";MAXY:", fileprop.length); + fileprop.length -= tmp; + tmp = 0; + Get_Value(buf, ";MINZ:", tmp); + Get_Value(buf, ";MAXZ:", fileprop.height); + fileprop.height -= tmp; + posptr = strstr(buf, tbstart); + if (posptr != NULL) { + fileprop.thumbstart = indx + (posptr - &buf[0]); + } + else { + indx += _MAX(10, nbyte - (signed)strlen(tbstart)); + card.setIndex(indx); + } + } + } + + if (!fileprop.thumbstart) { + card.closefile(); + LCD_MESSAGE_F("Thumbnail not found"); + return 0; + } + + // Get the size of the thumbnail + card.setIndex(fileprop.thumbstart + strlen(tbstart)); + for (uint8_t i = 0; i < 16; i++) { + char c = card.get(); + if (!ISEOL(c)) { + buf[i] = c; + } + else { + buf[i] = 0; + break; + } + } + fileprop.thumbsize = atoi(buf); + + // Exit if there isn't a thumbnail + if (!fileprop.thumbsize) { + card.closefile(); + LCD_MESSAGE_F("Invalid Thumbnail Size"); + return 0; + } + + uint16_t readed = 0; + uint8_t buf64[fileprop.thumbsize]; + + fileprop.thumbdata = new uint8_t[3 + 3 * (fileprop.thumbsize / 4)]; // Reserve space for the JPEG thumbnail + + while (readed < fileprop.thumbsize) { + uint8_t c = card.get(); + if (!ISEOL(c) && (c != ';') && (c != ' ')) { + buf64[readed] = c; + readed++; + } + } + card.closefile(); + buf64[readed] = 0; + + fileprop.thumbsize = decode_base64(buf64, fileprop.thumbdata); card.closefile(); + DWINUI::WriteToSRAM(0x00, fileprop.thumbsize, fileprop.thumbdata); + delete[] fileprop.thumbdata; + return true; +} + +void Preview_DrawFromSD() { + if (Has_Preview()) { + char buf[46]; + char str_1[6] = ""; + char str_2[6] = ""; + char str_3[6] = ""; + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 0, DWIN_WIDTH, STATUS_Y - 1); + if (fileprop.time) { + sprintf_P(buf, PSTR("Estimated time: %i:%02i"), (uint16_t)fileprop.time / 3600, ((uint16_t)fileprop.time % 3600) / 60); + DWINUI::Draw_String(20, 10, buf); + } + if (fileprop.filament) { + sprintf_P(buf, PSTR("Filament used: %s m"), dtostrf(fileprop.filament, 1, 2, str_1)); + DWINUI::Draw_String(20, 30, buf); + } + if (fileprop.layer) { + sprintf_P(buf, PSTR("Layer height: %s mm"), dtostrf(fileprop.layer, 1, 2, str_1)); + DWINUI::Draw_String(20, 50, buf); + } + if (fileprop.width) { + sprintf_P(buf, PSTR("Volume: %sx%sx%s mm"), dtostrf(fileprop.width, 1, 1, str_1), dtostrf(fileprop.length, 1, 1, str_2), dtostrf(fileprop.height, 1, 1, str_3)); + DWINUI::Draw_String(20, 70, buf); + } + DWINUI::Draw_Button(BTN_Print, 26, 290); + DWINUI::Draw_Button(BTN_Cancel, 146, 290); + DWIN_ICON_Show(0, 0, 1, 21, 90, 0x00); + Draw_Select_Highlight(true, 290); + DWIN_UpdateLCD(); + } + else { + HMI_flag.select_flag = 1; + wait_for_user = false; + } +} + +bool Preview_Valid() { + return !!fileprop.thumbstart; +} + +void Preview_Reset() { + fileprop.thumbsize = 0; +} + +#endif // HAS_GCODE_PREVIEW +#endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.h b/Marlin/src/lcd/e3v2/proui/gcode_preview.h new file mode 100644 index 000000000000..4417084a242d --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.h @@ -0,0 +1,27 @@ +/** + * DWIN g-code thumbnail preview + * Author: Miguel A. Risco-Castillo + * version: 2.1 + * Date: 2021/06/19 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as + * published by the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see . + * + * For commercial applications additional licenses can be requested + */ + +#pragma once + +void Preview_DrawFromSD(); +bool Preview_Valid(); +void Preview_Reset(); diff --git a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp b/Marlin/src/lcd/e3v2/proui/lockscreen.cpp index 2895c01544b0..44b595096a88 100644 --- a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp +++ b/Marlin/src/lcd/e3v2/proui/lockscreen.cpp @@ -23,8 +23,8 @@ /** * Lock screen implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 2.1 - * Date: 2021/11/09 + * Version: 2.2.0 + * Date: 2022/04/11 */ #include "../../../inc/MarlinConfigPre.h" @@ -50,11 +50,11 @@ void LockScreenClass::init() { } void LockScreenClass::draw() { - Title.SetCaption(PSTR("Lock Screen")); - DWINUI::ClearMenuArea(); + Title.SetCaption(GET_TEXT_F(MSG_LOCKSCREEN)); + DWINUI::ClearMainArea(); DWINUI::Draw_Icon(ICON_LOGO, 71, 120); // CREALITY logo - DWINUI::Draw_CenteredString(Color_White, 180, F("Printer is Locked,")); - DWINUI::Draw_CenteredString(Color_White, 200, F("Scroll to unlock.")); + DWINUI::Draw_CenteredString(Color_White, 180, GET_TEXT_F(MSG_LOCKSCREEN_LOCKED)); + DWINUI::Draw_CenteredString(Color_White, 200, GET_TEXT_F(MSG_LOCKSCREEN_UNLOCK)); DWINUI::Draw_CenteredString(Color_White, 240, F("-> | <-")); DWIN_Draw_Box(1, HMI_data.Barfill_Color, 0, 260, DWIN_WIDTH, 20); DWIN_Draw_VLine(Color_Yellow, lock_pos * DWIN_WIDTH / 255, 260, 20); diff --git a/Marlin/src/lcd/e3v2/proui/lockscreen.h b/Marlin/src/lcd/e3v2/proui/lockscreen.h index ec967fe2db7c..83d5530be3e4 100644 --- a/Marlin/src/lcd/e3v2/proui/lockscreen.h +++ b/Marlin/src/lcd/e3v2/proui/lockscreen.h @@ -24,8 +24,8 @@ /** * Lock screen implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 2.1 - * Date: 2021/11/09 + * Version: 2.2.0 + * Date: 2022/04/11 */ #include "../common/encoder.h" diff --git a/Marlin/src/lcd/e3v2/proui/menus.cpp b/Marlin/src/lcd/e3v2/proui/menus.cpp index 6dfcb8595c87..6438545cb251 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.cpp +++ b/Marlin/src/lcd/e3v2/proui/menus.cpp @@ -23,8 +23,8 @@ /** * Menu functions for ProUI * Author: Miguel A. Risco-Castillo - * Version: 1.2.1 - * Date: 2022/02/25 + * Version: 1.4.1 + * Date: 2022/04/14 * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU Lesser General Public License as @@ -51,6 +51,14 @@ #include "dwin.h" #include "menus.h" +int8_t MenuItemTotal = 0; +int8_t MenuItemCount = 0; +MenuItemClass** MenuItems = nullptr; +MenuClass *CurrentMenu = nullptr; +MenuClass *PreviousMenu = nullptr; +void (*onMenuDraw)(MenuClass* menu) = nullptr; +void (*onCursorErase)(const int8_t line) = nullptr; +void (*onCursorDraw)(const int8_t line) = nullptr; MenuData_t MenuData; // Menuitem Drawing functions ================================================= @@ -69,11 +77,13 @@ void Draw_Menu(MenuClass* menu) { } void Draw_Menu_Cursor(const int8_t line) { - DWIN_Draw_Rectangle(1, HMI_data.Cursor_color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); + const uint16_t ypos = MYPOS(line); + DWINUI::Draw_Box(1, HMI_data.Cursor_color, {0, ypos, 15, MLINE - 1}); } void Erase_Menu_Cursor(const int8_t line) { - DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); + const uint16_t ypos = MYPOS(line); + DWINUI::Draw_Box(1, HMI_data.Background_Color, {0, ypos, 15, MLINE - 1}); } void Draw_Menu_Line(const uint8_t line, const uint8_t icon /*=0*/, const char * const label /*=nullptr*/, bool more /*=false*/) { @@ -84,7 +94,7 @@ void Draw_Menu_Line(const uint8_t line, const uint8_t icon /*=0*/, const char * } void Draw_Chkb_Line(const uint8_t line, const bool checked) { - DWINUI::Draw_Checkbox(HMI_data.Text_Color, HMI_data.Background_Color, VALX + 16, MBASE(line) - 1, checked); + DWINUI::Draw_Checkbox(HMI_data.Text_Color, HMI_data.Background_Color, VALX + 3 * DWINUI::fontWidth(), MBASE(line) - 1, checked); } void Draw_Menu_IntValue(uint16_t bcolor, const uint8_t line, uint8_t iNum, const int32_t value /*=0*/) { @@ -141,11 +151,21 @@ void onDrawPFloat2Menu(MenuItemClass* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, value); } +void onDrawPFloat3Menu(MenuItemClass* menuitem, int8_t line) { + const float value = *(float*)static_cast(menuitem)->value; + onDrawFloatMenu(menuitem, line, 3, value); +} + void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line, bool checked) { onDrawMenuItem(menuitem, line); Draw_Chkb_Line(line, checked); } +void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line) { + const bool val = *(bool*)static_cast(menuitem)->value; + onDrawChkbMenu(menuitem, line, val); +} + //----------------------------------------------------------------------------- // On click functions //----------------------------------------------------------------------------- @@ -165,7 +185,7 @@ void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, MenuData.dp = dp; MenuData.Apply = Apply; MenuData.LiveUpdate = LiveUpdate; - MenuData.Value = val; + MenuData.Value = constrain(val, lo, hi); EncoderRate.enabled = true; } @@ -257,6 +277,7 @@ void HMI_Menu() { // 1 : live change // 2 : apply change int8_t HMI_GetIntNoDraw(const int32_t lo, const int32_t hi) { + const int32_t cval = MenuData.Value; EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (Apply_Encoder(encoder_diffState, MenuData.Value)) { @@ -265,9 +286,8 @@ int8_t HMI_GetIntNoDraw(const int32_t lo, const int32_t hi) { return 2; } LIMIT(MenuData.Value, lo, hi); - return 1; } - return 0; + return int8_t(cval != MenuData.Value); } // Get an integer value using the encoder @@ -367,4 +387,166 @@ void HMI_SetPFloat() { } } +// Menu Classes =============================================================== + +MenuClass::MenuClass() { + selected = 0; + topline = 0; +} + +void MenuClass::draw() { + MenuTitle.draw(); + if (onMenuDraw != nullptr) onMenuDraw(this); + for (int8_t i = 0; i < MenuItemCount; i++) + MenuItems[i]->draw(i - topline); + if (onCursorDraw != nullptr) onCursorDraw(line()); + DWIN_UpdateLCD(); +} + +void MenuClass::onScroll(bool dir) { + int8_t sel = selected; + if (dir) sel++; else sel--; + LIMIT(sel, 0, MenuItemCount - 1); + if (sel != selected) { + if (onCursorErase != nullptr) onCursorErase(line()); + DWIN_UpdateLCD(); + if ((sel - topline) == TROWS) { + DWIN_Frame_AreaMove(1, DWIN_SCROLL_UP, MLINE, DWINUI::backcolor, 0, TITLE_HEIGHT + 1, DWIN_WIDTH, STATUS_Y - 1); + topline++; + MenuItems[sel]->draw(TROWS - 1); + } + if ((sel < topline)) { + DWIN_Frame_AreaMove(1, DWIN_SCROLL_DOWN, MLINE, DWINUI::backcolor, 0, TITLE_HEIGHT + 1, DWIN_WIDTH, STATUS_Y - 1); + topline--; + MenuItems[sel]->draw(0); + } + selected = sel; + if (onCursorDraw != nullptr) onCursorDraw(line()); + DWIN_UpdateLCD(); + } +} + +void MenuClass::onClick() { + if (MenuItems[selected]->onClick != nullptr) (*MenuItems[selected]->onClick)(); +} + +MenuItemClass *MenuClass::SelectedItem() { + return MenuItems[selected]; +} + +MenuItemClass** MenuClass::Items() { + return MenuItems; +} + +int8_t MenuClass::count() { + return MenuItemCount; +}; + +/* MenuItem Class ===========================================================*/ + +MenuItemClass::MenuItemClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)()) { + icon = cicon; + onClick = onclick; + onDraw = ondraw; + const uint8_t len = _MIN(sizeof(caption) - 1, strlen(text)); + memcpy(&caption[0], text, len); + caption[len] = '\0'; +} + +MenuItemClass::MenuItemClass(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)()) { + icon = cicon; + onClick = onclick; + onDraw = ondraw; + caption[0] = '\0'; + frameid = id; + frame = { x1, y1, x2, y2 }; +} + +void MenuItemClass::SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { + caption[0] = '\0'; + frameid = id; + frame = { x1, y1, x2, y2 }; +} + +void MenuItemClass::draw(int8_t line) { + if (line < 0 || line >= TROWS) return; + if (onDraw != nullptr) (*onDraw)(this, line); +}; + +void MenuItemClass::redraw() { + draw(CurrentMenu->line(this->pos)); +} + +MenuItemPtrClass::MenuItemPtrClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) : MenuItemClass(cicon, text, ondraw, onclick) { + value = val; +}; + +// Menu auxiliary functions =================================================== + +void MenuItemsClear() { + if (MenuItems == nullptr) return; + for (int8_t i = 0; i < MenuItemCount; i++) delete MenuItems[i]; + delete[] MenuItems; + MenuItems = nullptr; + MenuItemCount = 0; + MenuItemTotal = 0; +} + +void MenuItemsPrepare(int8_t totalitems) { + MenuItemsClear(); + MenuItemTotal = totalitems; + MenuItems = new MenuItemClass*[totalitems]; +} + +MenuItemClass* MenuItemsAdd(MenuItemClass* menuitem) { + MenuItems[MenuItemCount] = menuitem; + menuitem->pos = MenuItemCount++; + return menuitem; +} + +MenuItemClass* MenuItemsAdd(uint8_t cicon, const char * const text/*=nullptr*/, void (*ondraw)(MenuItemClass* menuitem, int8_t line)/*=nullptr*/, void (*onclick)()/*=nullptr*/) { + if (MenuItemCount < MenuItemTotal) { + MenuItemClass* menuitem = new MenuItemClass(cicon, text, ondraw, onclick); + return MenuItemsAdd(menuitem); + } + else return nullptr; +} + +MenuItemClass* MenuItemsAdd(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line)/*=nullptr*/, void (*onclick)()/*=nullptr*/) { + if (MenuItemCount < MenuItemTotal) { + MenuItemClass* menuitem = new MenuItemClass(cicon, id, x1, y1, x2, y2, ondraw, onclick); + return MenuItemsAdd(menuitem); + } + else return nullptr; +} + +MenuItemClass* MenuItemsAdd(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) { + if (MenuItemCount < MenuItemTotal) { + MenuItemClass* menuitem = new MenuItemPtrClass(cicon, text, ondraw, onclick, val); + return MenuItemsAdd(menuitem); + } + else return nullptr; +} + +bool SetMenu(MenuClass* &menu, FSTR_P title, int8_t totalitems) { + if (!menu) menu = new MenuClass(); + const bool NotCurrent = (CurrentMenu != menu); + if (NotCurrent) { + menu->MenuTitle.SetCaption(title); + MenuItemsPrepare(totalitems); + } + return NotCurrent; +} + +void UpdateMenu(MenuClass* &menu) { + if (!menu) return; + if (CurrentMenu != menu) { + PreviousMenu = CurrentMenu; + CurrentMenu = menu; + } + menu->draw(); +} + +void ReDrawMenu() { if (CurrentMenu && checkkey==Menu) CurrentMenu->draw(); } + #endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/menus.h b/Marlin/src/lcd/e3v2/proui/menus.h index 0147c1616b31..d4514d173237 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.h +++ b/Marlin/src/lcd/e3v2/proui/menus.h @@ -23,8 +23,8 @@ /** * Menu functions for ProUI * Author: Miguel A. Risco-Castillo - * Version: 1.2.1 - * Date: 2022/02/25 + * Version: 1.4.1 + * Date: 2022/04/14 * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU Lesser General Public License as @@ -56,8 +56,70 @@ typedef struct { } MenuData_t; extern MenuData_t MenuData; +extern void (*onCursorErase)(const int8_t line); +extern void (*onCursorDraw)(const int8_t line); + +// Auxiliary Macros =========================================================== + +// Create and add a MenuItem object to the menu array +#define BACK_ITEM(H) MenuItemsAdd(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, H) +#define MENU_ITEM(V...) MenuItemsAdd(V) +#define EDIT_ITEM(V...) MenuItemsAdd(V) +#define MENU_ITEM_F(I,L,V...) MenuItemsAdd(I, GET_TEXT_F(L), V) +#define EDIT_ITEM_F(I,L,V...) MenuItemsAdd(I, GET_TEXT_F(L), V) + +// Menu Classes =============================================================== + +class MenuItemClass { +protected: +public: + int8_t pos = 0; + uint8_t icon = 0; + char caption[32] = ""; + uint8_t frameid = 0; + rect_t frame = {0}; + void (*onDraw)(MenuItemClass* menuitem, int8_t line) = nullptr; + void (*onClick)() = nullptr; + MenuItemClass() {}; + MenuItemClass(uint8_t cicon, const char * const text=nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); + // MenuItemClass(uint8_t cicon, FSTR_P text = nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr) : MenuItemClass(cicon, FTOP(text), ondraw, onclick){} + MenuItemClass(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); + void SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); + virtual ~MenuItemClass(){}; + virtual void draw(int8_t line); + void redraw(); +}; + +class MenuItemPtrClass: public MenuItemClass { +public: + void *value = nullptr; + using MenuItemClass::MenuItemClass; + MenuItemPtrClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val); + MenuItemPtrClass(uint8_t cicon, FSTR_P text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) : MenuItemPtrClass(cicon, FTOP(text), ondraw, onclick, val){} +}; + +class MenuClass { +public: + int8_t topline = 0; + int8_t selected = 0; + TitleClass MenuTitle; + MenuClass(); + virtual ~MenuClass(){}; + inline int8_t line() { return selected - topline; }; + inline int8_t line(uint8_t pos) {return pos - topline; }; + int8_t count(); + virtual void draw(); + virtual void onScroll(bool dir); + void onClick(); + MenuItemClass* SelectedItem(); + static MenuItemClass** Items(); +}; +extern MenuClass *CurrentMenu; +extern MenuClass *PreviousMenu; +extern void (*onMenuDraw)(MenuClass* menu); // Menuitem Drawing functions ================================================= + void Draw_Title(TitleClass* title); void Draw_Menu(MenuClass* menu); void Draw_Menu_Cursor(const int8_t line); @@ -74,9 +136,12 @@ void onDrawPInt32Menu(MenuItemClass* menuitem, int8_t line); void onDrawFloatMenu(MenuItemClass* menuitem, int8_t line, uint8_t dp, const float value); void onDrawPFloatMenu(MenuItemClass* menuitem, int8_t line); void onDrawPFloat2Menu(MenuItemClass* menuitem, int8_t line); +void onDrawPFloat3Menu(MenuItemClass* menuitem, int8_t line); void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line, bool checked); +void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line); // On click functions ========================================================= + void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); void SetValueOnClick(uint8_t process, const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); @@ -86,9 +151,38 @@ void SetFloatOnClick(const float lo, const float hi, uint8_t dp, const float val void SetPFloatOnClick(const float lo, const float hi, uint8_t dp, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); // HMI user control functions ================================================= + void HMI_Menu(); void HMI_SetInt(); void HMI_SetPInt(); void HMI_SetIntNoDraw(); void HMI_SetFloat(); void HMI_SetPFloat(); + +// Menu auxiliary functions =================================================== + +// Create a new menu +bool SetMenu(MenuClass* &menu, FSTR_P title, int8_t totalitems); + +//Update the Menu and Draw if it is valid +void UpdateMenu(MenuClass* &menu); + +//Redraw the current Menu if it is valid +void ReDrawMenu(); + +// Clear MenuItems array and free MenuItems elements +void MenuItemsClear(); + +// Prepare MenuItems array +void MenuItemsPrepare(int8_t totalitems); + +// Add elements to the MenuItems array +MenuItemClass* MenuItemsAdd(uint8_t cicon, const char * const text=nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); +inline MenuItemClass* MenuItemsAdd(uint8_t cicon, FSTR_P text = nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr) { + return MenuItemsAdd(cicon, FTOP(text), ondraw, onclick); +} +MenuItemClass* MenuItemsAdd(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); +MenuItemClass* MenuItemsAdd(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val); +inline MenuItemClass* MenuItemsAdd(uint8_t cicon, FSTR_P text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) { + return MenuItemsAdd(cicon, FTOP(text), ondraw, onclick, val); +} diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp index 0b22ae98d5ef..c2d01a07eb76 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp @@ -23,8 +23,8 @@ /** * Mesh Viewer for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * version: 3.12.1 - * Date: 2022/02/24 + * version: 3.14.1 + * Date: 2022/04/11 */ #include "../../../inc/MarlinConfigPre.h" @@ -41,6 +41,10 @@ #include "dwin_popup.h" #include "../../../feature/bedlevel/bedlevel.h" +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "ubl_tools.h" +#endif + MeshViewerClass MeshViewer; void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8_t sizey) { @@ -56,29 +60,29 @@ void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8 #define DrawMeshValue(xp, yp, zv) DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(xp) - 18, py(yp) - 6, zv) #define DrawMeshHLine(yp) DWIN_Draw_HLine(HMI_data.SplitLine_Color, px(0), py(yp), DWIN_WIDTH - 2 * mx) #define DrawMeshVLine(xp) DWIN_Draw_VLine(HMI_data.SplitLine_Color, px(xp), py(sizey - 1), DWIN_WIDTH - 2 * my) - int16_t maxz =-32000; int16_t minz = 32000; avg = 0; + int16_t maxz =-32000; int16_t minz = 32000; LOOP_L_N(y, sizey) LOOP_L_N(x, sizex) { const float v = isnan(zval[x][y]) ? 0 : round(zval[x][y] * 100); zmesh[x][y] = v; - avg += v; NOLESS(maxz, v); NOMORE(minz, v); } max = (float)maxz / 100; min = (float)minz / 100; - avg = avg / (100 * sizex * sizey); - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); DWIN_Draw_Rectangle(0, HMI_data.SplitLine_Color, px(0), py(0), px(sizex - 1), py(sizey - 1)); LOOP_S_L_N(x, 1, sizex - 1) DrawMeshVLine(x); LOOP_S_L_N(y, 1, sizey - 1) DrawMeshHLine(y); LOOP_L_N(y, sizey) { - watchdog_refresh(); + hal.watchdog_refresh(); LOOP_L_N(x, sizex) { uint16_t color = DWINUI::RainbowInt(zmesh[x][y], _MIN(-5, minz), _MAX(5, maxz)); uint8_t radius = rm(zmesh[x][y]); DWINUI::Draw_FillCircle(color, px(x), py(y), radius); - if (sizex < 9) - DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(x) - 18, py(y) - 6, zval[x][y]); + if (sizex < 9) { + if (zmesh[x][y] == 0) DWINUI::Draw_Float(font6x12, 1, 2, px(x) - 12, py(y) - 6, 0); + else DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(x) - 18, py(y) - 6, zval[x][y]); + } else { char str_1[9]; str_1[0] = 0; @@ -90,7 +94,7 @@ void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8 sprintf_P(str_1, PSTR("-.%02i"), -zmesh[x][y]); break; case 0: - DWIN_Draw_String(false, font6x12, DWINUI::textcolor, DWINUI::backcolor, px(x) - 4, py(y) - 6, "0");; + DWIN_Draw_String(false, font6x12, DWINUI::textcolor, DWINUI::backcolor, px(x) - 4, py(y) - 6, "0"); break; case 1 ... 99: sprintf_P(str_1, PSTR(".%02i"), zmesh[x][y]); @@ -107,22 +111,35 @@ void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8 } void MeshViewerClass::Draw(bool withsave /*= false*/) { - Title.ShowCaption(F("Mesh Viewer")); - DrawMesh(Z_VALUES_ARR, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y); + Title.ShowCaption(GET_TEXT_F(MSG_MESH_VIEWER)); + #if ENABLED(USE_UBL_VIEWER) + DWINUI::ClearMainArea(); + ubl_tools.viewer_print_value = true; + ubl_tools.Draw_Bed_Mesh(-1, 1, 8, 10 + TITLE_HEIGHT); + #else + DrawMesh(bedlevel.z_values, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y); + #endif if (withsave) { DWINUI::Draw_Button(BTN_Save, 26, 305); DWINUI::Draw_Button(BTN_Continue, 146, 305); Draw_Select_Highlight(HMI_flag.select_flag, 305); - } else DWINUI::Draw_Button(BTN_Continue, 86, 305); - char str_1[6], str_2[6] = ""; - ui.status_printf(0, F("Mesh minZ: %s, maxZ: %s"), - dtostrf(min, 1, 2, str_1), - dtostrf(max, 1, 2, str_2) - ); + } + else + DWINUI::Draw_Button(BTN_Continue, 86, 305); + + #if ENABLED(USE_UBL_VIEWER) + ubl_tools.Set_Mesh_Viewer_Status(); + #else + char str_1[6], str_2[6] = ""; + ui.status_printf(0, F("Mesh minZ: %s, maxZ: %s"), + dtostrf(min, 1, 2, str_1), + dtostrf(max, 1, 2, str_2) + ); + #endif } void Draw_MeshViewer() { MeshViewer.Draw(true); } -void onClick_MeshViewer() { if (HMI_flag.select_flag) WriteEeprom(); HMI_ReturnScreen(); } -void Goto_MeshViewer() { if (leveling_is_valid()) Goto_Popup(Draw_MeshViewer, onClick_MeshViewer); else HMI_ReturnScreen(); } +void onClick_MeshViewer() { if (HMI_flag.select_flag) SaveMesh(); HMI_ReturnScreen(); } +void Goto_MeshViewer() { if (leveling_is_valid()) Goto_Popup(Draw_MeshViewer, onClick_MeshViewer); else HMI_ReturnScreen(); } #endif // DWIN_LCD_PROUI && HAS_MESH diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.h b/Marlin/src/lcd/e3v2/proui/meshviewer.h index f914bab4ae23..1e78ff2657b8 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.h +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.h @@ -27,13 +27,13 @@ /** * Mesh Viewer for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * version: 3.12.1 - * Date: 2022/02/24 + * version: 3.14.1 + * Date: 2022/04/11 */ class MeshViewerClass { public: - float avg, max, min; + float max, min; void Draw(bool withsave = false); void DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8_t sizey); }; diff --git a/Marlin/src/lcd/e3v2/proui/plot.cpp b/Marlin/src/lcd/e3v2/proui/plot.cpp new file mode 100644 index 000000000000..ebc685fa2453 --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/plot.cpp @@ -0,0 +1,94 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 Single var plot + * Author: Miguel A. Risco-Castillo + * Version: 2.0 + * Date: 2022/01/31 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as + * published by the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see . + * + * For commercial applications additional licenses can be requested + */ + +#include "../../../inc/MarlinConfigPre.h" + +#ifdef DWIN_LCD_PROUI + +#include "plot.h" + +#include "../../../core/types.h" +#include "../../marlinui.h" +#include "dwin_lcd.h" +#include "dwinui.h" +#include "dwin_popup.h" +#include "dwin.h" + +#define Plot_Bg_Color RGB( 1, 12, 8) + +PlotClass Plot; + +uint16_t grphpoints, r, x2, y2 = 0; +frame_rect_t grphframe = {0}; +float scale = 0; + +void PlotClass::Draw(const frame_rect_t frame, const float max, const float ref) { + grphframe = frame; + grphpoints = 0; + scale = frame.h / max; + x2 = frame.x + frame.w - 1; + y2 = frame.y + frame.h - 1; + r = round((y2) - ref * scale); + DWINUI::Draw_Box(1, Plot_Bg_Color, frame); + for (uint8_t i = 1; i < 4; i++) if (i*50 < frame.w) DWIN_Draw_VLine(Line_Color, i*50 + frame.x, frame.y, frame.h); + DWINUI::Draw_Box(0, Color_White, DWINUI::ExtendFrame(frame, 1)); + DWIN_Draw_HLine(Color_Red, frame.x, r, frame.w); +} + +void PlotClass::Update(const float value) { + if (!scale) return; + uint16_t y = round((y2) - value * scale); + if (grphpoints < grphframe.w) { + DWIN_Draw_Point(Color_Yellow, 1, 1, grphpoints + grphframe.x, y); + } + else { + DWIN_Frame_AreaMove(1, 0, 1, Plot_Bg_Color, grphframe.x, grphframe.y, x2, y2); + if ((grphpoints % 50) == 0) DWIN_Draw_VLine(Line_Color, x2 - 1, grphframe.y + 1, grphframe.h - 2); + DWIN_Draw_Point(Color_Red, 1, 1, x2 - 1, r); + DWIN_Draw_Point(Color_Yellow, 1, 1, x2 - 1, y); + } + grphpoints++; +} + +#endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/plot.h b/Marlin/src/lcd/e3v2/proui/plot.h new file mode 100644 index 000000000000..8522c530bd3f --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/plot.h @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 Single var plot + * Author: Miguel A. Risco-Castillo + * Version: 1.0 + * Date: 2022/01/30 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as + * published by the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see . + * + * For commercial applications additional licenses can be requested + */ +#pragma once + +#include "dwinui.h" + +class PlotClass { +public: + void Draw(frame_rect_t frame, float max, float ref = 0); + void Update(float value); +}; + +extern PlotClass Plot; diff --git a/Marlin/src/lcd/e3v2/proui/printstats.cpp b/Marlin/src/lcd/e3v2/proui/printstats.cpp index d4ca4ca2255f..5a7b6c9c4170 100644 --- a/Marlin/src/lcd/e3v2/proui/printstats.cpp +++ b/Marlin/src/lcd/e3v2/proui/printstats.cpp @@ -50,7 +50,7 @@ void PrintStatsClass::Draw() { constexpr int8_t MRG = 30; Title.ShowCaption(GET_TEXT_F(MSG_INFO_STATS_MENU)); - DWINUI::ClearMenuArea(); + DWINUI::ClearMainArea(); Draw_Popup_Bkgd(); DWINUI::Draw_Button(BTN_Continue, 86, 250); printStatistics ps = print_job_timer.getStats(); @@ -71,7 +71,7 @@ void PrintStatsClass::Draw() { void PrintStatsClass::Reset() { print_job_timer.initStats(); - HMI_AudioFeedback(); + DONE_BUZZ(true); } void Goto_PrintStats() { diff --git a/Marlin/src/lcd/e3v2/proui/ubl_tools.cpp b/Marlin/src/lcd/e3v2/proui/ubl_tools.cpp new file mode 100644 index 000000000000..87909d2dd2a2 --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/ubl_tools.cpp @@ -0,0 +1,260 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * UBL Tools and Mesh Viewer for Pro UI + * Version: 1.0.0 + * Date: 2022/04/13 + * + * Original Author: Henri-J-Norden + * Original Source: https://github.com/Jyers/Marlin/pull/126 + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(DWIN_LCD_PROUI, AUTO_BED_LEVELING_UBL) + +#include "ubl_tools.h" +#include "../../marlinui.h" +#include "../../../core/types.h" +#include "dwin.h" +#include "dwinui.h" +#include "dwin_popup.h" +#include "../../../feature/bedlevel/bedlevel.h" +#include "../../../module/probe.h" +#include "../../../gcode/gcode.h" +#include "../../../module/planner.h" +#include "../../../gcode/queue.h" +#include "../../../libs/least_squares_fit.h" +#include "../../../libs/vector_3.h" + +UBLMeshToolsClass ubl_tools; + +#if ENABLED(USE_UBL_VIEWER) + bool UBLMeshToolsClass::viewer_asymmetric_range = false; + bool UBLMeshToolsClass::viewer_print_value = false; +#endif +bool UBLMeshToolsClass::goto_mesh_value = false; +uint8_t UBLMeshToolsClass::tilt_grid = 1; + +bool drawing_mesh = false; +char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16], str_3[16]; + +#if ENABLED(AUTO_BED_LEVELING_UBL) + + void UBLMeshToolsClass::manual_value_update(const uint8_t mesh_x, const uint8_t mesh_y, bool undefined/*=false*/) { + sprintf_P(cmd, PSTR("M421 I%i J%i Z%s %s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1), undefined ? "N" : ""); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + } + + bool UBLMeshToolsClass::create_plane_from_mesh() { + struct linear_fit_data lsf_results; + incremental_LSF_reset(&lsf_results); + GRID_LOOP(x, y) { + if (!isnan(bedlevel.z_values[x][y])) { + xy_pos_t rpos = { bedlevel.get_mesh_x(x), bedlevel.get_mesh_y(y) }; + incremental_LSF(&lsf_results, rpos, bedlevel.z_values[x][y]); + } + } + + if (finish_incremental_LSF(&lsf_results)) { + SERIAL_ECHOPGM("Could not complete LSF!"); + return true; + } + + bedlevel.set_all_mesh_points_to_value(0); + + matrix_3x3 rotation = matrix_3x3::create_look_at(vector_3(lsf_results.A, lsf_results.B, 1)); + GRID_LOOP(i, j) { + float mx = bedlevel.get_mesh_x(i), + my = bedlevel.get_mesh_y(j), + mz = bedlevel.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); + } + + rotation.apply_rotation_xyz(mx, my, mz); + + 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); + } + + bedlevel.z_values[i][j] = mz - lsf_results.D; + } + return false; + } + +#else + + void UBLMeshToolsClass::manual_value_update(const uint8_t mesh_x, const uint8_t mesh_y) { + sprintf_P(cmd, PSTR("G29 I%i J%i Z%s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + } + +#endif + +void UBLMeshToolsClass::manual_move(const uint8_t mesh_x, const uint8_t mesh_y, bool zmove/*=false*/) { + if (zmove) { + planner.synchronize(); + current_position.z = goto_mesh_value ? bedlevel.z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + } + else { + DWIN_Show_Popup(ICON_BLTouch, F("Moving to Point"), F("Please wait until done.")); + HMI_SaveProcessID(NothingToDo); + sprintf_P(cmd, PSTR("G0 F300 Z%s"), dtostrf(Z_CLEARANCE_BETWEEN_PROBES, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + sprintf_P(cmd, PSTR("G42 F4000 I%i J%i"), mesh_x, mesh_y); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + current_position.z = goto_mesh_value ? bedlevel.z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + HMI_ReturnScreen(); + } +} + +float UBLMeshToolsClass::get_max_value() { + float max = __FLT_MIN__; + GRID_LOOP(x, y) { + if (!isnan(bedlevel.z_values[x][y]) && bedlevel.z_values[x][y] > max) + max = bedlevel.z_values[x][y]; + } + return max; +} + +float UBLMeshToolsClass::get_min_value() { + float min = __FLT_MAX__; + GRID_LOOP(x, y) { + if (!isnan(bedlevel.z_values[x][y]) && bedlevel.z_values[x][y] < min) + min = bedlevel.z_values[x][y]; + } + return min; +} + +bool UBLMeshToolsClass::validate() { + float min = __FLT_MAX__, max = __FLT_MIN__; + + GRID_LOOP(x, y) { + if (isnan(bedlevel.z_values[x][y])) return false; + if (bedlevel.z_values[x][y] < min) min = bedlevel.z_values[x][y]; + if (bedlevel.z_values[x][y] > max) max = bedlevel.z_values[x][y]; + } + return max <= UBL_Z_OFFSET_MAX && min >= UBL_Z_OFFSET_MIN; +} + +#if ENABLED(USE_UBL_VIEWER) + void UBLMeshToolsClass::Draw_Bed_Mesh(int16_t selected /*= -1*/, uint8_t gridline_width /*= 1*/, uint16_t padding_x /*= 8*/, uint16_t padding_y_top /*= 40 + 53 - 7*/) { + drawing_mesh = true; + const uint16_t total_width_px = DWIN_WIDTH - padding_x - padding_x; + const uint16_t cell_width_px = total_width_px / (GRID_MAX_POINTS_X); + const uint16_t cell_height_px = total_width_px / (GRID_MAX_POINTS_Y); + const float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = _MAX(v_min, v_max); + + // Clear background from previous selection and select new square + DWIN_Draw_Rectangle(1, Color_Bg_Black, _MAX(0, padding_x - gridline_width), _MAX(0, padding_y_top - gridline_width), padding_x + total_width_px, padding_y_top + total_width_px); + if (selected >= 0) { + const auto selected_y = selected / (GRID_MAX_POINTS_X); + const auto selected_x = selected - (GRID_MAX_POINTS_X) * selected_y; + const auto start_y_px = padding_y_top + selected_y * cell_height_px; + const auto start_x_px = padding_x + selected_x * cell_width_px; + DWIN_Draw_Rectangle(1, Color_White, _MAX(0, start_x_px - gridline_width), _MAX(0, start_y_px - gridline_width), start_x_px + cell_width_px, start_y_px + cell_height_px); + } + + // Draw value square grid + char buf[8]; + GRID_LOOP(x, y) { + const auto start_x_px = padding_x + x * cell_width_px; + const auto end_x_px = start_x_px + cell_width_px - 1 - gridline_width; + const auto start_y_px = padding_y_top + ((GRID_MAX_POINTS_Y) - y - 1) * cell_height_px; + const auto end_y_px = start_y_px + cell_height_px - 1 - gridline_width; + DWIN_Draw_Rectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ + isnan(bedlevel.z_values[x][y]) ? Color_Grey : ( // gray if undefined + (bedlevel.z_values[x][y] < 0 ? + (uint16_t)round(0x1F * -bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? range : v_min)) << 11 : // red if mesh point value is negative + (uint16_t)round(0x3F * bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? range : v_max)) << 5) | // green if mesh point value is positive + _MIN(0x1F, (((uint8_t)abs(bedlevel.z_values[x][y]) / 10) * 4))), // + blue stepping for every mm + start_x_px, start_y_px, end_x_px, end_y_px + ); + + safe_delay(10); + LCD_SERIAL.flushTX(); + + // Draw value text on + if (viewer_print_value) { + int8_t offset_x, offset_y = cell_height_px / 2 - 6; + if (isnan(bedlevel.z_values[x][y])) { // undefined + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); + } + else { // has value + if (GRID_MAX_POINTS_X < 10) + sprintf_P(buf, PSTR("%s"), dtostrf(abs(bedlevel.z_values[x][y]), 1, 2, str_1)); + else + sprintf_P(buf, PSTR("%02i"), (uint16_t)(abs(bedlevel.z_values[x][y] - (int16_t)bedlevel.z_values[x][y]) * 100)); + offset_x = cell_width_px / 2 - 3 * (strlen(buf)) - 2; + if (!(GRID_MAX_POINTS_X < 10)) + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, buf); + } + safe_delay(10); + LCD_SERIAL.flushTX(); + } + } + } + + void UBLMeshToolsClass::Set_Mesh_Viewer_Status() { // TODO: draw gradient with values as a legend instead + float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = _MAX(v_min, v_max); + if (v_min > 3e+10F) v_min = 0.0000001; + if (v_max > 3e+10F) v_max = 0.0000001; + if (range > 3e+10F) range = 0.0000001; + char msg[46]; + if (viewer_asymmetric_range) { + dtostrf(-v_min, 1, 3, str_1); + dtostrf( v_max, 1, 3, str_2); + } + else { + dtostrf(-range, 1, 3, str_1); + dtostrf( range, 1, 3, str_2); + } + sprintf_P(msg, PSTR("Red %s..0..%s Green"), str_1, str_2); + ui.set_status(msg); + drawing_mesh = false; + } +#endif + +#endif // DWIN_LCD_PROUI && AUTO_BED_LEVELING_UBL diff --git a/Marlin/src/lcd/e3v2/proui/ubl_tools.h b/Marlin/src/lcd/e3v2/proui/ubl_tools.h new file mode 100644 index 000000000000..563794a46385 --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/ubl_tools.h @@ -0,0 +1,59 @@ +/** + * UBL Tools and Mesh Viewer for Pro UI + * Version: 1.0.0 + * Date: 2022/04/13 + * + * Original Author: Henri-J-Norden (https://github.com/Henri-J-Norden) + * Original Source: https://github.com/Jyers/Marlin/pull/135 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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" + +//#define USE_UBL_VIEWER 1 + +#define UBL_Z_OFFSET_MIN -3.0 +#define UBL_Z_OFFSET_MAX 3.0 + +class UBLMeshToolsClass { +public: + #if ENABLED(USE_UBL_VIEWER) + static bool viewer_asymmetric_range; + static bool viewer_print_value; + #endif + static bool goto_mesh_value; + static uint8_t tilt_grid; + + #if ENABLED(AUTO_BED_LEVELING_UBL) + static void manual_value_update(const uint8_t mesh_x, const uint8_t mesh_y, bool undefined=false); + static bool create_plane_from_mesh(); + #else + static void manual_value_update(const uint8_t mesh_x, const uint8_t mesh_y); + #endif + static void manual_move(const uint8_t mesh_x, const uint8_t mesh_y, bool zmove=false); + static float get_max_value(); + static float get_min_value(); + static bool validate(); + #if ENABLED(USE_UBL_VIEWER) + static void Draw_Bed_Mesh(int16_t selected = -1, uint8_t gridline_width = 1, uint16_t padding_x = 8, uint16_t padding_y_top = 40 + 53 - 7); + static void Set_Mesh_Viewer_Status(); + #endif +}; + +extern UBLMeshToolsClass ubl_tools; + +void Goto_MeshViewer(); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp index f228c471c9ca..adbf98e3bb82 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp @@ -35,6 +35,8 @@ #include "../../../inc/MarlinConfigPre.h" +// TODO: Use Marlin's built-in tone player instead. + #if ENABLED(ANYCUBIC_LCD_CHIRON) #include "Tunes.h" @@ -44,15 +46,12 @@ namespace Anycubic { void PlayTune(uint8_t beeperPin, const uint16_t *tune, uint8_t speed=1) { uint8_t pos = 1; - uint16_t wholenotelen = tune[0] / speed; + const uint16_t wholenotelen = tune[0] / speed; do { - uint16_t freq = tune[pos]; - uint16_t notelen = wholenotelen / tune[pos + 1]; - + const uint16_t freq = tune[pos], notelen = wholenotelen / tune[pos + 1]; ::tone(beeperPin, freq, notelen); ExtUI::delay_ms(notelen); pos += 2; - if (pos >= MAX_TUNE_LENGTH) break; } while (tune[pos] != n_END); } diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 7561c89d79bf..285729cc15d2 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -708,7 +708,7 @@ void ChironTFT::PanelAction(uint8_t req) { // 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 + // Send a G-code-relative non-print move and let the controller deal with it // G91 G0 G90 if (!isPrinting()) { // Ignore request if printing diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp index 469202ee222b..40a670b5b073 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp @@ -42,9 +42,7 @@ namespace ExtUI { 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 + TERN_(SPEAKER, ::tone(BEEPER_PIN, frequency, duration)); } void onPrintTimerStarted() { AnycubicTFT.OnPrintTimerStarted(); } void onPrintTimerPaused() { AnycubicTFT.OnPrintTimerPaused(); } diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index c382af3fe2e5..0da8bb36a780 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -86,7 +86,7 @@ void AnycubicTFTClass::OnSetup() { delay_ms(10); // Init the state of the key pins running on the TFT - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) + #if BOTH(SDSUPPORT, HAS_SD_DETECT) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) @@ -916,7 +916,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { } void AnycubicTFTClass::DoSDCardStateCheck() { - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) + #if BOTH(SDSUPPORT, HAS_SD_DETECT) bool isInserted = isMediaInserted(); if (isInserted) SENDLINE_DBG_PGM("J00", "TFT Serial Debug: SD card state changed... isInserted"); diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp index 6fa188bf5ff3..0eb95bb041ba 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp @@ -243,7 +243,7 @@ void DGUSDisplay::WritePGM(const char str[], uint8_t len) { } void DGUSDisplay::loop() { - // protect against recursion… ProcessRx() may indirectly call idle() when injecting gcode commands. + // Protect against recursion. ProcessRx() may indirectly call idle() when injecting G-code commands. if (!no_reentrance) { no_reentrance = true; ProcessRx(); diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 5d8349e6f8a9..0e9fd37758cc 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -474,13 +474,8 @@ void DGUSScreenHandler::HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr void DGUSScreenHandler::HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr) { DEBUG_ECHOLNPGM("HandleMotorLockUnlock"); - - char buf[4]; - const int16_t lock = BE16_P(val_ptr); - strcpy_P(buf, lock ? PSTR("M18") : PSTR("M17")); - - //DEBUG_ECHOPGM(" ", buf); - queue.enqueue_one_now(buf); + const int16_t lock = BE16_P(*(uint16_t*)val_ptr); + queue.enqueue_one_now(lock ? F("M18") : F("M17")); } void DGUSScreenHandler::HandleSettings(DGUS_VP_Variable &var, void *val_ptr) { @@ -547,23 +542,23 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo #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); + queue.enqueue_one_now(buf); break; #endif #if HAS_MULTI_HOTEND case VP_PID_AUTOTUNE_E1: sprintf_P(buf, PSTR("M303 E%d C5 S210 U1"), ExtUI::extruder_t::E1); + queue.enqueue_one_now(buf); break; #endif #endif #if ENABLED(PIDTEMPBED) case VP_PID_AUTOTUNE_BED: - strcpy_P(buf, PSTR("M303 E-1 C5 S70 U1")); + queue.enqueue_one_now(F("M303 E-1 C5 S70 U1")); break; #endif } - if (buf[0]) queue.enqueue_one_now(buf); - #if ENABLED(DGUS_UI_WAITING) sendinfoscreen(F("PID is autotuning"), F("please wait"), NUL_STR, NUL_STR, true, true, true, true); GotoScreen(DGUSLCD_SCREEN_WAITING); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index 9ec2304a36aa..bdcd248dd6cd 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -680,8 +680,8 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; 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_Info_PrintFinish_1_Dis = 0x5C00; + constexpr uint16_t VP_Info_PrintFinish_2_Dis = 0x5C10; constexpr uint16_t VP_Length_Dis = 0x5B00; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 86758a90bb53..78d43f3a4c07 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -190,7 +190,6 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. switch (BE16_P(val_ptr)) { case 0: { // Resume - auto cs = getCurrentScreen(); if (runout_mks.runout_status != RUNOUT_WAITING_STATUS && runout_mks.runout_status != UNRUNOUT_STATUS) { if (cs == MKSLCD_SCREEN_PRINT || cs == MKSLCD_SCREEN_PAUSE) @@ -210,7 +209,6 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { } break; case 1: // Pause - GotoScreen(MKSLCD_SCREEN_PAUSE); if (!ExtUI::isPrintingFromMediaPaused()) { nozzle_park_mks.print_pause_start_flag = 1; @@ -219,6 +217,7 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { //ExtUI::mks_pausePrint(); } break; + case 2: // Abort HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); break; @@ -256,7 +255,7 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { ) filelist.refresh(); } - void DGUSScreenHandler::SDPrintingFinished() { + void DGUSScreenHandlerMKS::SDPrintingFinished() { if (DGUSAutoTurnOff) { queue.exhaust(); gcode.process_subcommands_now(F("M81")); @@ -414,15 +413,15 @@ void DGUSScreenHandlerMKS::LanguageChange(DGUS_VP_Variable &var, void *val_ptr) case MKS_SimpleChinese: DGUS_LanguageDisplay(MKS_SimpleChinese); mks_language_index = MKS_SimpleChinese; - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_Choose); - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_NoChoose); + dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_Choose); + dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_NoChoose); settings.save(); break; case MKS_English: DGUS_LanguageDisplay(MKS_English); mks_language_index = MKS_English; - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_NoChoose); - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_Choose); + dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_NoChoose); + dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_Choose); settings.save(); break; default: break; @@ -561,7 +560,7 @@ void DGUSScreenHandlerMKS::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { queue.enqueue_now(F("G29S2")); mesh_point_count--; if (mks_language_index == MKS_English) { - const char level_buf_en2[] = "Level Finsh"; + const char level_buf_en2[] = "Leveling Done"; dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en2, 32, true); } else if (mks_language_index == MKS_SimpleChinese) { @@ -1121,7 +1120,6 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr) #if ENABLED(BABYSTEPPING) void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { DEBUG_ECHOLNPGM("HandleLiveAdjustZ"); - char babystep_buf[30]; const float step = ZOffset_distance; const uint16_t flag = BE16_P(val_ptr); @@ -1138,7 +1136,7 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr) else queue.inject(F("M290 Z-0.01")); - z_offset_add = z_offset_add - ZOffset_distance; + z_offset_add -= ZOffset_distance; break; case 1: @@ -1153,7 +1151,7 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr) else queue.inject(F("M290 Z-0.01")); - z_offset_add = z_offset_add + ZOffset_distance; + z_offset_add += ZOffset_distance; break; default: break; @@ -1434,12 +1432,12 @@ bool DGUSScreenHandlerMKS::loop() { void DGUSScreenHandlerMKS::LanguagePInit() { switch (mks_language_index) { case MKS_SimpleChinese: - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_Choose); - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_NoChoose); + dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_Choose); + dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_NoChoose); break; case MKS_English: - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_NoChoose); - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_Choose); + dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_NoChoose); + dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_Choose); break; default: break; @@ -1697,8 +1695,8 @@ void DGUSScreenHandlerMKS::DGUS_LanguageDisplay(uint8_t var) { 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 Info_PrintFinish_1_buf_en[] = "Print Done"; + dgusdisplay.WriteVariable(VP_Info_PrintFinish_1_Dis, Info_PrintFinish_1_buf_en, 32, true); const char TMC_X_Step_buf_en[] = "X_SenSitivity"; dgusdisplay.WriteVariable(VP_TMC_X_Step_Dis, TMC_X_Step_buf_en, 32, true); @@ -1961,8 +1959,8 @@ void DGUSScreenHandlerMKS::DGUS_LanguageDisplay(uint8_t var) { 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 Info_PrintFinish_1_buf_ch[] = { 0xF2B4, 0xA1D3, 0xEACD, 0xC9B3, 0x2000 }; + dgusdisplay.WriteVariable(VP_Info_PrintFinish_1_Dis, Info_PrintFinish_1_buf_ch, 32, true); const uint16_t TMC_X_Current_buf_ch[] = { 0x2058, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; dgusdisplay.WriteVariable(VP_TMC_X_Current_Dis, TMC_X_Current_buf_ch, 16, true); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index cf95bb1d761d..88fe30a0273f 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -47,9 +47,7 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { if (vp.addr == DGUS_Addr::SCREENCHANGE_SD) { #if ENABLED(SDSUPPORT) - #if !PIN_EXISTS(SD_DETECT) - card.mount(); - #endif + IF_DISABLED(HAS_SD_DETECT, card.mount()); if (!ExtUI::isMediaInserted()) { dgus_screen_handler.SetStatusMessage(GET_TEXT_F(MSG_NO_MEDIA)); @@ -466,7 +464,7 @@ void DGUSRxHandler::MoveToPoint(DGUS_VP &vp, void *data_ptr) { } const uint8_t point = ((uint8_t*)data_ptr)[1]; - constexpr float lfrb[4] = LEVEL_CORNERS_INSET_LFRB; + constexpr float lfrb[4] = BED_TRAMMING_INSET_LFRB; float x, y; switch (point) { @@ -493,12 +491,12 @@ void DGUSRxHandler::MoveToPoint(DGUS_VP &vp, void *data_ptr) { break; } - if (ExtUI::getAxisPosition_mm(ExtUI::Z) < Z_MIN_POS + LEVEL_CORNERS_Z_HOP) { - ExtUI::setAxisPosition_mm(Z_MIN_POS + LEVEL_CORNERS_Z_HOP, ExtUI::Z); + if (ExtUI::getAxisPosition_mm(ExtUI::Z) < Z_MIN_POS + BED_TRAMMING_Z_HOP) { + ExtUI::setAxisPosition_mm(Z_MIN_POS + BED_TRAMMING_Z_HOP, ExtUI::Z); } ExtUI::setAxisPosition_mm(x, ExtUI::X); ExtUI::setAxisPosition_mm(y, ExtUI::Y); - ExtUI::setAxisPosition_mm(Z_MIN_POS + LEVEL_CORNERS_HEIGHT, ExtUI::Z); + ExtUI::setAxisPosition_mm(Z_MIN_POS + BED_TRAMMING_HEIGHT, ExtUI::Z); } void DGUSRxHandler::Probe(DGUS_VP &vp, void *data_ptr) { diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp index 6388e1683d05..0b584fac3bce 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp @@ -200,7 +200,7 @@ void DGUSScreenHandler::StoreSettings(char *buff) { data.initialized = true; data.volume = dgus_display.GetVolume(); data.brightness = dgus_display.GetBrightness(); - data.abl = (ExtUI::getLevelingActive() && ExtUI::getMeshValid()); + data.abl_okay = (ExtUI::getLevelingActive() && ExtUI::getMeshValid()); memcpy(buff, &data, sizeof(data)); } @@ -216,8 +216,7 @@ void DGUSScreenHandler::LoadSettings(const char *buff) { dgus_display.SetBrightness(data.initialized ? data.brightness : DGUS_DEFAULT_BRIGHTNESS); if (data.initialized) { - leveling_active = (data.abl && ExtUI::getMeshValid()); - + leveling_active = (data.abl_okay && ExtUI::getMeshValid()); ExtUI::setLevelingActive(leveling_active); } } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h index 509d59920066..cc59bda6d7fa 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h @@ -134,7 +134,7 @@ class DGUSScreenHandler { bool initialized; uint8_t volume; uint8_t brightness; - bool abl; + bool abl_okay; } eeprom_data_t; }; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp index 961b29ca2236..62df84e53d8f 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp @@ -341,8 +341,8 @@ void DGUSTxHandler::ABLGrid(DGUS_VP &vp) { int16_t fixed; for (int i = 0; i < DGUS_LEVEL_GRID_SIZE; i++) { - point.x = i % GRID_MAX_POINTS_X; - point.y = i / GRID_MAX_POINTS_X; + point.x = i % (GRID_MAX_POINTS_X); + point.y = i / (GRID_MAX_POINTS_X); fixed = dgus_display.ToFixedPoint(ExtUI::getMeshPoint(point)); data[i] = Swap16(fixed); } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h index 9b275fb2f550..846fd1594216 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h @@ -71,15 +71,15 @@ static_assert((DGUS_LEVEL_GRID_SIZE == GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y), " #define DGUS_DEFAULT_FILAMENT_LEN 10 #endif -#ifndef LEVEL_CORNERS_Z_HOP - #define LEVEL_CORNERS_Z_HOP 4.0 +#ifndef BED_TRAMMING_Z_HOP + #define BED_TRAMMING_Z_HOP 4.0 #endif -#ifndef LEVEL_CORNERS_HEIGHT - #define LEVEL_CORNERS_HEIGHT 0.0 +#ifndef BED_TRAMMING_HEIGHT + #define BED_TRAMMING_HEIGHT 0.0 #endif -static_assert(LEVEL_CORNERS_Z_HOP >= 0, "LEVEL_CORNERS_Z_HOP must be >= 0. Please update your configuration."); +static_assert(BED_TRAMMING_Z_HOP >= 0, "BED_TRAMMING_Z_HOP must be >= 0. Please update your configuration."); #ifndef DGUS_LEVEL_CENTER_X #define DGUS_LEVEL_CENTER_X ((X_BED_SIZE) / 2) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index dbee1e034b07..a23ad6e37e76 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -178,9 +178,9 @@ bool UIFlashStorage::is_present = false; if (!is_known) { SERIAL_ECHO_MSG("Unable to locate supported SPI Flash Memory."); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(" Manufacturer ID, got: ", manufacturer_id); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(" Device Type , got: ", device_type); - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(" Capacity , got: ", capacity); + SERIAL_ECHO_MSG(" Manufacturer ID, got: ", manufacturer_id); + SERIAL_ECHO_MSG(" Device Type , got: ", device_type); + SERIAL_ECHO_MSG(" Capacity , got: ", capacity); } return is_known; @@ -247,7 +247,7 @@ bool UIFlashStorage::is_present = false; case 0xFFFFFFFFul: return read_offset; case delimiter: read_offset = offset; break; default: - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Invalid delimiter in Flash: ", delim); + SERIAL_ECHO_MSG("Invalid delimiter in Flash: ", delim); return -1; } } @@ -325,8 +325,7 @@ bool UIFlashStorage::is_present = false; } SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Writing UI settings to SPI Flash (offset ", write_addr); - SERIAL_ECHOPGM(")..."); + SERIAL_ECHOPGM("Writing UI settings to SPI Flash (offset ", write_addr, ")..."); const uint32_t delim = delimiter; write_addr = write(write_addr, &delim, sizeof(delim)); @@ -509,7 +508,7 @@ bool UIFlashStorage::is_present = false; bytes_remaining = get_media_file_size(slot); if (bytes_remaining != 0xFFFFFFFFUL) { - SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Boot media file size:", bytes_remaining); + SERIAL_ECHO_MSG("Boot media file size:", bytes_remaining); addr = get_media_file_start(slot); return true; } 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 index 6d42fd41e4dd..e3b95c4cd490 100644 --- 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 @@ -54,7 +54,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .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(8) .button(BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MAX_SPEED)) .tag(9) .button(BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) .tag(10) .button(BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(TERN(HAS_JUNCTION_DEVIATION, MSG_JUNCTION_DEVIATION, MSG_JERK))) .enabled(ENABLED(BACKLASH_GCODE)) @@ -64,7 +64,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .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)); + .tag(1) .button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp index 79a49c79a631..4af38dcb9df7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp @@ -32,12 +32,12 @@ using namespace Theme; #define GRID_COLS 2 #define GRID_ROWS 9 -void BioPrintingDialogBox::draw_status_message(draw_mode_t what, const char *message) { +void BioPrintingDialogBox::draw_status_message(draw_mode_t what, const char *cmsg) { 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); + draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(2,2), cmsg, OPT_CENTER, font_large); } } @@ -105,26 +105,30 @@ bool BioPrintingDialogBox::onTouchEnd(uint8_t tag) { return true; } -void BioPrintingDialogBox::setStatusMessage(FSTR_P message) { - char buff[strlen_P(FTOP(message)) + 1]; - strcpy_P(buff, FTOP(message)); - setStatusMessage(buff); +void BioPrintingDialogBox::setStatusMessage(FSTR_P fmsg) { + #ifdef __AVR__ + char buff[strlen_P(FTOP(fmsg)) + 1]; + strcpy_P(buff, FTOP(fmsg)); + setStatusMessage(buff); + #else + setStatusMessage(FTOP(fmsg)); + #endif } -void BioPrintingDialogBox::setStatusMessage(const char *message) { +void BioPrintingDialogBox::setStatusMessage(const char *cmsg) { CommandProcessor cmd; cmd.cmd(CMD_DLSTART) .cmd(CLEAR_COLOR_RGB(bg_color)) .cmd(CLEAR(true,true,true)); - draw_status_message(BACKGROUND, message); + draw_status_message(BACKGROUND, cmsg); draw_progress(BACKGROUND); draw_time_remaining(BACKGROUND); draw_interaction_buttons(BACKGROUND); storeBackground(); #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_MSG("New status message: ", message); + SERIAL_ECHO_MSG("New status message: ", cmsg); #endif if (AT_SCREEN(BioPrintingDialogBox)) 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 index a6674bed90b6..9fb56bce11f7 100644 --- 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 @@ -122,7 +122,7 @@ void StatusScreen::draw_temperature(draw_mode_t what) { ui.bounds(POLY(bed_temp), x, y, h, v); cmd.text(x, y, h, v, str); - #endif + #endif } } @@ -354,8 +354,8 @@ bool StatusScreen::onTouchHeld(uint8_t tag) { return false; } -void StatusScreen::setStatusMessage(FSTR_P pstr) { - BioPrintingDialogBox::setStatusMessage(pstr); +void StatusScreen::setStatusMessage(FSTR_P fstr) { + BioPrintingDialogBox::setStatusMessage(fstr); } void StatusScreen::setStatusMessage(const char * const str) { 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 index 888f2c2cdd24..00cdf76331d6 100644 --- 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 @@ -59,7 +59,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .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(5) .button(VELOCITY_POS, GET_TEXT_F(MSG_MAX_SPEED)) .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)) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 8e788421ad25..a796c8edcf5f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -1024,9 +1024,7 @@ template bool CLCD::CommandFifo::write(T data, uint16_t len) { uint16_t Command_Space = mem_read_32(REG::CMDB_SPACE) & 0x0FFF; if (Command_Space < (len + padding)) { #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Waiting for ", len + padding); - SERIAL_ECHOLNPGM(" bytes in command queue, now free: ", Command_Space); + SERIAL_ECHO_MSG("Waiting for ", len + padding, " bytes in command queue, now free: ", Command_Space); #endif do { Command_Space = mem_read_32(REG::CMDB_SPACE) & 0x0FFF; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index da911c772daa..6b2dc9eb4498 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -240,8 +240,8 @@ #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 NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'. + #define _BOOL(x) NOT(NOT(x)) // _BOOL('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)) diff --git a/Marlin/src/lcd/extui/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 index 1ee73c140e3a..f947a352b1f1 100644 --- a/Marlin/src/lcd/extui/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 @@ -131,9 +131,7 @@ bool DLCache::store(uint32_t min_bytes /* = 0*/) { if (dl_size > dl_slot_size) { // Not enough memory to cache the display list. #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOPGM ("Not enough space in GRAM to cache display list, free space: ", dl_slot_size); - SERIAL_ECHOLNPGM(" Required: ", dl_size); + SERIAL_ECHO_MSG("Not enough space in GRAM to cache display list, free space: ", dl_slot_size, " Required: ", dl_size); #endif dl_slot_used = 0; save_slot(); @@ -141,9 +139,7 @@ bool DLCache::store(uint32_t min_bytes /* = 0*/) { } else { #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOPGM ("Saving DL to RAMG cache, bytes: ", dl_slot_used); - SERIAL_ECHOLNPGM(" Free space: ", dl_slot_size); + SERIAL_ECHO_MSG("Saving DL to RAMG cache, bytes: ", dl_slot_used, " Free space: ", dl_slot_size); #endif dl_slot_used = dl_size; save_slot(); @@ -160,9 +156,9 @@ void DLCache::save_slot(uint8_t indx, uint32_t addr, uint16_t size, uint16_t use } void DLCache::load_slot(uint8_t indx, uint32_t &addr, uint16_t &size, uint16_t &used) { - addr = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 0); - size = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 4); - used = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 8); + addr = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 0); + size = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 4); + used = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 8); } void DLCache::append() { @@ -171,9 +167,7 @@ void DLCache::append() { #if ENABLED(TOUCH_UI_DEBUG) cmd.execute(); wait_until_idle(); - SERIAL_ECHO_START(); - SERIAL_ECHOPGM ("Appending to DL from RAMG cache, bytes: ", dl_slot_used); - SERIAL_ECHOLNPGM(" REG_CMD_DL: ", CLCD::mem_read_32(REG::CMD_DL)); + SERIAL_ECHO_MSG("Appending to DL from RAMG cache, bytes: ", dl_slot_used, " REG_CMD_DL: ", CLCD::mem_read_32(REG::CMD_DL)); #endif } 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 index c75cdf18121a..d2f95d1f6e79 100644 --- 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 @@ -136,9 +136,13 @@ namespace FTDI { } void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P fstr, uint16_t options, uint8_t font) { - char str[strlen_P(FTOP(fstr)) + 1]; - strcpy_P(str, FTOP(fstr)); - draw_text_box(cmd, x, y, w, h, (const char*) str, options, font); + #ifdef __AVR__ + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); + draw_text_box(cmd, x, y, w, h, (const char*) str, options, font); + #else + draw_text_box(cmd, x, y, w, h, FTOP(fstr), options, font); + #endif } } // namespace FTDI diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index ab52a59b9acc..6f189155f5de 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -192,9 +192,13 @@ } uint16_t FTDI::get_utf8_text_width(FSTR_P fstr, font_size_t fs) { - char str[strlen_P(FTOP(fstr)) + 1]; - strcpy_P(str, FTOP(fstr)); - return get_utf8_text_width(str, fs); + #ifdef __AVR__ + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); + return get_utf8_text_width(str, fs); + #else + return get_utf8_text_width(FTOP(fstr), fs); + #endif } /** diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp index 8e0a01e1c8a3..8753b44e709b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp @@ -105,7 +105,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .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(5) .button(VELOCITY_POS, GET_TEXT_F(MSG_MAX_SPEED)) .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)) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp index b6f69bc33e95..a006d30942d9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp @@ -32,7 +32,7 @@ using namespace Theme; #define GRID_ROWS 8 template -void DialogBoxBaseClass::drawMessage(T message, int16_t font) { +void DialogBoxBaseClass::drawMessage(T message, const int16_t font) { CommandProcessor cmd; cmd.cmd(CMD_DLSTART) .cmd(CLEAR_COLOR_RGB(bg_color)) @@ -43,8 +43,7 @@ void DialogBoxBaseClass::drawMessage(T message, int16_t font) { cmd.colors(normal_btn); } -template void DialogBoxBaseClass::drawMessage(const char *, int16_t font); -template void DialogBoxBaseClass::drawMessage(FSTR_P, int16_t font); +template void DialogBoxBaseClass::drawMessage(PGM_P const, const int16_t); void DialogBoxBaseClass::drawYesNoButtons(uint8_t default_btn) { CommandProcessor cmd; 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 index c87640992866..fc05560b8cac 100644 --- 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 @@ -27,12 +27,15 @@ class DialogBoxBaseClass : public BaseScreen { protected: - template static void drawMessage(T, int16_t font = 0); + template static void drawMessage(T, const int16_t font=0); + static void drawMessage(FSTR_P const fstr, const int16_t font=0) { drawMessage(FTOP(fstr), font); } + template static void drawButton(T); static void drawYesNoButtons(uint8_t default_btn = 0); static void drawOkayButton(); - static void onRedraw(draw_mode_t) {}; + static void onRedraw(draw_mode_t) {} + public: static bool onTouchEnd(uint8_t tag); static void onIdle(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp index 011127621120..e7fc23ab4870 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp @@ -34,7 +34,7 @@ void MaxVelocityScreen::onRedraw(draw_mode_t what) { widgets_t w(what); w.precision(0); w.units(GET_TEXT_F(MSG_UNITS_MM_S)); - w.heading( GET_TEXT_F(MSG_VELOCITY)); + w.heading( GET_TEXT_F(MSG_MAX_SPEED)); w.color(x_axis) .adjuster( 2, GET_TEXT_F(MSG_VMAX_X), getAxisMaxFeedrate_mm_s(X) ); w.color(y_axis) .adjuster( 4, GET_TEXT_F(MSG_VMAX_Y), getAxisMaxFeedrate_mm_s(Y) ); w.color(z_axis) .adjuster( 6, GET_TEXT_F(MSG_VMAX_Z), getAxisMaxFeedrate_mm_s(Z) ); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp index 43f33fb3bf0b..f1c65357e017 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -332,10 +332,14 @@ void StatusScreen::draw_status_message(draw_mode_t what, const char *message) { } } -void StatusScreen::setStatusMessage(FSTR_P message) { - char buff[strlen_P(FTOP(message)) + 1]; - strcpy_P(buff, FTOP(message)); - setStatusMessage((const char *) buff); +void StatusScreen::setStatusMessage(FSTR_P fmsg) { + #ifdef __AVR__ + char buff[strlen_P(FTOP(fmsg)) + 1]; + strcpy_P(buff, FTOP(fmsg)); + setStatusMessage((const char *)buff); + #else + setStatusMessage(FTOP(fmsg)); + #endif } void StatusScreen::setStatusMessage(const char *message) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp index 4fd060eb2e40..0370c4417478 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp @@ -41,8 +41,6 @@ void TuneMenu::onRedraw(draw_mode_t what) { } #if ENABLED(TOUCH_UI_PORTRAIT) - #define GRID_COLS 2 - #define GRID_ROWS 9 #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) @@ -54,8 +52,6 @@ void TuneMenu::onRedraw(draw_mode_t what) { #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_COLS 2 - #define GRID_ROWS 5 #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) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h index cbc05c5aa3b0..8c123db6a1f7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h @@ -20,4 +20,6 @@ ****************************************************************************/ #pragma once +#define LSTR PROGMEM Language_Str + #include "language_en.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h index 83e762430ce1..5dbde8a5c359 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h @@ -36,142 +36,142 @@ #endif namespace Language_en { - PROGMEM Language_Str MSG_BUTTON_OKAY = u8"Okay"; - PROGMEM Language_Str MSG_BUTTON_MENU = u8"Menu"; - PROGMEM Language_Str MSG_BUTTON_MEDIA = u8"Media"; - PROGMEM Language_Str MSG_BUTTON_OPEN = u8"Open"; - PROGMEM Language_Str MSG_CLEAN_NOZZLE = u8"Clean Nozzle"; - PROGMEM Language_Str MSG_VMAX_X = u8"Vmax X"; - PROGMEM Language_Str MSG_VMAX_Y = u8"Vmax Y"; - PROGMEM Language_Str MSG_VMAX_Z = u8"Vmax Z"; - PROGMEM Language_Str MSG_ACCEL_PRINTING = u8"Printing"; - PROGMEM Language_Str MSG_ACCEL_TRAVEL = u8"Travel"; - PROGMEM Language_Str MSG_ACCEL_RETRACT = u8"Retraction"; - PROGMEM Language_Str MSG_AMAX_X = u8"Amax X"; - PROGMEM Language_Str MSG_AMAX_Y = u8"Amax Y"; - PROGMEM Language_Str MSG_AMAX_Z = u8"Amax Z"; - PROGMEM Language_Str MSG_AXIS_X = u8"X"; - PROGMEM Language_Str MSG_AXIS_X2 = u8"X2"; - PROGMEM Language_Str MSG_AXIS_Y = u8"Y"; - PROGMEM Language_Str MSG_AXIS_Y2 = u8"Y2"; - PROGMEM Language_Str MSG_AXIS_Z = u8"Z"; - PROGMEM Language_Str MSG_AXIS_Z2 = u8"Z2"; - PROGMEM Language_Str MSG_AXIS_E = u8"E"; - PROGMEM Language_Str MSG_AXIS_E1 = u8"E1"; - PROGMEM Language_Str MSG_AXIS_E2 = u8"E2"; - PROGMEM Language_Str MSG_AXIS_E3 = u8"E3"; - PROGMEM Language_Str MSG_AXIS_E4 = u8"E4"; - PROGMEM Language_Str MSG_AXIS_ALL = u8"All"; - PROGMEM Language_Str MSG_HOME = u8"Home"; - PROGMEM Language_Str MSG_PRINT_STARTING = u8"Print starting"; - PROGMEM Language_Str MSG_PRINT_FINISHED = u8"Print finished"; - PROGMEM Language_Str MSG_PRINT_ERROR = u8"Print error"; - PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_1 = u8"Color Touch Panel"; - PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = 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 " + LSTR MSG_BUTTON_OKAY = u8"Okay"; + LSTR MSG_BUTTON_MENU = u8"Menu"; + LSTR MSG_BUTTON_MEDIA = u8"Media"; + LSTR MSG_BUTTON_OPEN = u8"Open"; + LSTR MSG_CLEAN_NOZZLE = u8"Clean Nozzle"; + LSTR MSG_VMAX_X = u8"Max X Speed"; + LSTR MSG_VMAX_Y = u8"Max Y Speed"; + LSTR MSG_VMAX_Z = u8"Max Z Speed"; + LSTR MSG_ACCEL_PRINTING = u8"Printing"; + LSTR MSG_ACCEL_TRAVEL = u8"Travel"; + LSTR MSG_ACCEL_RETRACT = u8"Retraction"; + LSTR MSG_AMAX_X = u8"Max X Accel."; + LSTR MSG_AMAX_Y = u8"Max Y Accel."; + LSTR MSG_AMAX_Z = u8"Max Z Accel."; + LSTR MSG_AXIS_X = u8"X"; + LSTR MSG_AXIS_X2 = u8"X2"; + LSTR MSG_AXIS_Y = u8"Y"; + LSTR MSG_AXIS_Y2 = u8"Y2"; + LSTR MSG_AXIS_Z = u8"Z"; + LSTR MSG_AXIS_Z2 = u8"Z2"; + LSTR MSG_AXIS_E = u8"E"; + LSTR MSG_AXIS_E1 = u8"E1"; + LSTR MSG_AXIS_E2 = u8"E2"; + LSTR MSG_AXIS_E3 = u8"E3"; + LSTR MSG_AXIS_E4 = u8"E4"; + LSTR MSG_AXIS_ALL = u8"All"; + LSTR MSG_HOME = u8"Home"; + LSTR MSG_PRINT_STARTING = u8"Print starting"; + LSTR MSG_PRINT_FINISHED = u8"Print finished"; + LSTR MSG_PRINT_ERROR = u8"Print error"; + LSTR MSG_ABOUT_TOUCH_PANEL_1 = u8"Color Touch Panel"; + LSTR MSG_ABOUT_TOUCH_PANEL_2 = WEBSITE_URL; + LSTR 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. 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"; - PROGMEM Language_Str MSG_DISPLAY_MENU = u8"Display"; - PROGMEM Language_Str MSG_INTERFACE = u8"Interface"; - PROGMEM Language_Str MSG_MEASURE_AUTOMATICALLY = u8"Measure automatically"; - PROGMEM Language_Str MSG_H_OFFSET = u8"H Offset"; - PROGMEM Language_Str MSG_V_OFFSET = u8"V Offset"; - PROGMEM Language_Str MSG_TOUCH_SCREEN = u8"Touch Screen"; - PROGMEM Language_Str MSG_CALIBRATE = u8"Calibrate"; - PROGMEM Language_Str MSG_UNITS_MILLIAMP = u8"mA"; - PROGMEM Language_Str MSG_UNITS_MM = u8"mm"; - PROGMEM Language_Str MSG_UNITS_MM_S = u8"mm/s"; - PROGMEM Language_Str MSG_UNITS_MM_S2 = u8"mm/s" SUPERSCRIPT_TWO; - PROGMEM Language_Str MSG_UNITS_STEP_MM = u8"st/mm"; - PROGMEM Language_Str MSG_UNITS_PERCENT = u8"%"; - PROGMEM Language_Str MSG_UNITS_C = DEGREE_SIGN u8"C"; - PROGMEM Language_Str MSG_IDLE = u8"idle"; - PROGMEM Language_Str MSG_SET_MAXIMUM = u8"Set Maximum"; - PROGMEM Language_Str MSG_PRINT_SPEED = u8"Print Speed"; - PROGMEM Language_Str MSG_LINEAR_ADVANCE = u8"Linear Advance"; - PROGMEM Language_Str MSG_LINEAR_ADVANCE_K = u8"K"; - PROGMEM Language_Str MSG_LINEAR_ADVANCE_K1 = u8"K E1"; - PROGMEM Language_Str MSG_LINEAR_ADVANCE_K2 = u8"K E2"; - PROGMEM Language_Str MSG_LINEAR_ADVANCE_K3 = u8"K E3"; - PROGMEM Language_Str MSG_LINEAR_ADVANCE_K4 = u8"K E4"; - PROGMEM Language_Str MSG_NUDGE_NOZZLE = u8"Nudge Nozzle"; - PROGMEM Language_Str MSG_ADJUST_BOTH_NOZZLES = u8"Adjust Both Nozzles"; - PROGMEM Language_Str MSG_SHOW_OFFSETS = u8"Show Offsets"; - PROGMEM Language_Str MSG_INCREMENT = u8"Increment"; - PROGMEM Language_Str MSG_ERASE_FLASH_WARNING = u8"Are you sure? SPI flash will be erased."; - PROGMEM Language_Str MSG_ERASING = u8"Erasing..."; - PROGMEM Language_Str MSG_ERASED = u8"SPI flash erased"; - PROGMEM Language_Str MSG_CALIBRATION_WARNING = u8"For best results, unload the filament and clean the hotend prior to starting calibration. Continue?"; - PROGMEM Language_Str MSG_START_PRINT_CONFIRMATION = u8"Start printing %s?"; - PROGMEM Language_Str MSG_ABORT_WARNING = u8"Are you sure you want to cancel the print?"; - PROGMEM Language_Str MSG_EXTRUDER_SELECTION = u8"Extruder Selection"; - PROGMEM Language_Str MSG_CURRENT_TEMPERATURE = u8"Current Temp"; - PROGMEM Language_Str MSG_REMOVAL_TEMPERATURE = u8"Removal Temp"; - 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/Extrude"; - PROGMEM Language_Str MSG_MOMENTARY = u8"Momentary"; - PROGMEM Language_Str MSG_CONTINUOUS = u8"Continuous"; - PROGMEM Language_Str MSG_PRINT_MENU = u8"Print Menu"; - PROGMEM Language_Str MSG_FINE_MOTION = u8"Fine motion"; - PROGMEM Language_Str MSG_ENABLE_MEDIA = u8"Enable Media"; - PROGMEM Language_Str MSG_INSERT_MEDIA = u8"Insert Media..."; - PROGMEM Language_Str MSG_LCD_BRIGHTNESS = u8"LCD brightness"; - PROGMEM Language_Str MSG_SOUND_VOLUME = u8"Sound volume"; - PROGMEM Language_Str MSG_SCREEN_LOCK = u8"Screen lock"; - PROGMEM Language_Str MSG_BOOT_SCREEN = u8"Boot screen"; - PROGMEM Language_Str MSG_SOUNDS = u8"Sounds"; - PROGMEM Language_Str MSG_CLICK_SOUNDS = u8"Click sounds"; - PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; - PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; - PROGMEM Language_Str MSG_EEPROM_SAVED = u8"Settings saved!"; - 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."; + LSTR MSG_RUNOUT_1 = u8"Runout 1"; + LSTR MSG_RUNOUT_2 = u8"Runout 2"; + LSTR MSG_DISPLAY_MENU = u8"Display"; + LSTR MSG_INTERFACE = u8"Interface"; + LSTR MSG_MEASURE_AUTOMATICALLY = u8"Measure automatically"; + LSTR MSG_H_OFFSET = u8"H Offset"; + LSTR MSG_V_OFFSET = u8"V Offset"; + LSTR MSG_TOUCH_SCREEN = u8"Touch Screen"; + LSTR MSG_CALIBRATE = u8"Calibrate"; + LSTR MSG_UNITS_MILLIAMP = u8"mA"; + LSTR MSG_UNITS_MM = u8"mm"; + LSTR MSG_UNITS_MM_S = u8"mm/s"; + LSTR MSG_UNITS_MM_S2 = u8"mm/s" SUPERSCRIPT_TWO; + LSTR MSG_UNITS_STEP_MM = u8"st/mm"; + LSTR MSG_UNITS_PERCENT = u8"%"; + LSTR MSG_UNITS_C = DEGREE_SIGN u8"C"; + LSTR MSG_IDLE = u8"idle"; + LSTR MSG_SET_MAXIMUM = u8"Set Maximum"; + LSTR MSG_PRINT_SPEED = u8"Print Speed"; + LSTR MSG_LINEAR_ADVANCE = u8"Linear Advance"; + LSTR MSG_LINEAR_ADVANCE_K = u8"K"; + LSTR MSG_LINEAR_ADVANCE_K1 = u8"K E1"; + LSTR MSG_LINEAR_ADVANCE_K2 = u8"K E2"; + LSTR MSG_LINEAR_ADVANCE_K3 = u8"K E3"; + LSTR MSG_LINEAR_ADVANCE_K4 = u8"K E4"; + LSTR MSG_NUDGE_NOZZLE = u8"Nudge Nozzle"; + LSTR MSG_ADJUST_BOTH_NOZZLES = u8"Adjust Both Nozzles"; + LSTR MSG_SHOW_OFFSETS = u8"Show Offsets"; + LSTR MSG_INCREMENT = u8"Increment"; + LSTR MSG_ERASE_FLASH_WARNING = u8"Are you sure? SPI flash will be erased."; + LSTR MSG_ERASING = u8"Erasing..."; + LSTR MSG_ERASED = u8"SPI flash erased"; + LSTR MSG_CALIBRATION_WARNING = u8"For best results, unload the filament and clean the hotend prior to starting calibration. Continue?"; + LSTR MSG_START_PRINT_CONFIRMATION = u8"Start printing %s?"; + LSTR MSG_ABORT_WARNING = u8"Are you sure you want to cancel the print?"; + LSTR MSG_EXTRUDER_SELECTION = u8"Extruder Selection"; + LSTR MSG_CURRENT_TEMPERATURE = u8"Current Temp"; + LSTR MSG_REMOVAL_TEMPERATURE = u8"Removal Temp"; + LSTR MSG_CAUTION = u8"Caution:"; + LSTR MSG_HOT = u8"Hot!"; + LSTR MSG_UNLOAD_FILAMENT = u8"Unload/Retract"; + LSTR MSG_LOAD_FILAMENT = u8"Load/Extrude"; + LSTR MSG_MOMENTARY = u8"Momentary"; + LSTR MSG_CONTINUOUS = u8"Continuous"; + LSTR MSG_PRINT_MENU = u8"Print Menu"; + LSTR MSG_FINE_MOTION = u8"Fine motion"; + LSTR MSG_ENABLE_MEDIA = u8"Enable Media"; + LSTR MSG_INSERT_MEDIA = u8"Insert Media..."; + LSTR MSG_LCD_BRIGHTNESS = u8"LCD brightness"; + LSTR MSG_SOUND_VOLUME = u8"Sound volume"; + LSTR MSG_SCREEN_LOCK = u8"Screen lock"; + LSTR MSG_BOOT_SCREEN = u8"Boot screen"; + LSTR MSG_SOUNDS = u8"Sounds"; + LSTR MSG_CLICK_SOUNDS = u8"Click sounds"; + LSTR MSG_EEPROM_RESTORED = u8"Settings restored from backup"; + LSTR MSG_EEPROM_RESET = u8"Settings restored to default"; + LSTR MSG_EEPROM_SAVED = u8"Settings saved!"; + LSTR MSG_EEPROM_SAVE_PROMPT = u8"Settings applied. Save these settings for next power-on?"; + LSTR MSG_EEPROM_RESET_WARNING = u8"Are you sure? Customizations will be lost."; - PROGMEM Language_Str MSG_PASSCODE_REJECTED = u8"Wrong passcode!"; - PROGMEM Language_Str MSG_PASSCODE_ACCEPTED = u8"Passcode accepted!"; - PROGMEM Language_Str MSG_PASSCODE_SELECT = u8"Select Passcode:"; - PROGMEM Language_Str MSG_PASSCODE_REQUEST = u8"Enter Passcode:"; + LSTR MSG_PASSCODE_REJECTED = u8"Wrong passcode!"; + LSTR MSG_PASSCODE_ACCEPTED = u8"Passcode accepted!"; + LSTR MSG_PASSCODE_SELECT = u8"Select Passcode:"; + LSTR MSG_PASSCODE_REQUEST = u8"Enter Passcode:"; - 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_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_AXIS_LEVELING = u8"Axis Leveling"; - PROGMEM Language_Str MSG_PROBE_BED = u8"Probe Mesh"; - PROGMEM Language_Str MSG_PRINT_TEST = u8"Print Test (PLA)"; - PROGMEM Language_Str MSG_MOVE_Z_TO_TOP = u8"Raise Z to Top"; + LSTR MSG_TOUCH_CALIBRATION_START = u8"Release to begin screen calibration"; + LSTR MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; + LSTR MSG_BED_MAPPING_DONE = u8"Bed mapping finished"; + LSTR MSG_BED_MAPPING_INCOMPLETE = u8"Not all points probed"; + LSTR MSG_LEVELING = u8"Leveling"; + LSTR MSG_AXIS_LEVELING = u8"Axis Leveling"; + LSTR MSG_PROBE_BED = u8"Probe Mesh"; + LSTR MSG_PRINT_TEST = u8"Print Test (PLA)"; + LSTR MSG_MOVE_Z_TO_TOP = u8"Raise Z to Top"; #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"; - PROGMEM Language_Str MSG_BED_TEMPERATURE = u8"Bed Temperature"; - PROGMEM Language_Str MSG_HOME_XYZ_WARNING = u8"About to move to home position. Ensure the top and the bed of the printer are clear.\n\nContinue?"; - PROGMEM Language_Str MSG_HOME_E_WARNING = u8"About to re-home plunger and auto-level. Remove syringe prior to proceeding.\n\nContinue?"; + LSTR MSG_MOVE_TO_HOME = u8"Move to Home"; + LSTR MSG_RAISE_PLUNGER = u8"Raise Plunger"; + LSTR MSG_RELEASE_XY_AXIS = u8"Release X and Y Axis"; + LSTR MSG_BED_TEMPERATURE = u8"Bed Temperature"; + LSTR MSG_HOME_XYZ_WARNING = u8"About to move to home position. Ensure the top and the bed of the printer are clear.\n\nContinue?"; + LSTR MSG_HOME_E_WARNING = u8"About to re-home plunger and auto-level. Remove syringe prior to proceeding.\n\nContinue?"; #endif #ifdef TOUCH_UI_COCOA_PRESS - 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"; + LSTR MSG_BODY = u8"Body"; + LSTR MSG_SELECT_CHOCOLATE_TYPE = u8"Select Chocolate Type"; + LSTR MSG_EXTERNAL = u8"External"; + LSTR MSG_CHOCOLATE = u8"Chocolate"; + LSTR MSG_UNLOAD_CARTRIDGE = u8"Unload Cartridge"; + LSTR MSG_LOAD_UNLOAD = u8"Load/Unload"; + LSTR MSG_FULL_LOAD = u8"Full Load"; + LSTR MSG_FULL_UNLOAD = u8"Full Unload"; + LSTR MSG_PREHEAT_CHOCOLATE = u8"Preheat Chocolate"; + LSTR MSG_PREHEAT_FINISHED = u8"Preheat finished"; + LSTR MSG_PREHEAT = u8"Preheat"; + LSTR MSG_BUTTON_PAUSE = u8"Pause"; + LSTR MSG_BUTTON_RESUME = u8"Resume"; + LSTR MSG_ELAPSED_PRINT = u8"Elapsed Print"; + LSTR MSG_XYZ_MOVE = u8"XYZ Move"; + LSTR MSG_E_MOVE = u8"Extrusion Move"; #endif }; // namespace Language_en diff --git a/Marlin/src/lcd/extui/malyan/malyan.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp index df7f305df2be..06c9886f0131 100644 --- a/Marlin/src/lcd/extui/malyan/malyan.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -24,7 +24,7 @@ * 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 + * on Serial1 for the M200 board. This module outputs a pseudo-G-code * wrapped in curly braces which the LCD implementation translates into * actual G-code commands. * diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp index ebad70859741..0199bc1f555d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp @@ -369,7 +369,7 @@ uint32_t lv_open_gcode_file(char *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 + // Ignore the beginning message of G-code file if (ps4) { pre_sread_cnt = (uintptr_t)ps4 - (uintptr_t)((uint32_t *)(&public_buf[0])); card.setIndex(pre_sread_cnt); @@ -402,7 +402,7 @@ void lv_gcode_file_read(uint8_t *data_buf) { char temp_test[200]; volatile uint16_t *p_index; - watchdog_refresh(); + hal.watchdog_refresh(); memset(public_buf, 0, 200); while (card.isFileOpen()) { @@ -490,7 +490,7 @@ void cutFileName(char *path, int len, int bytePerLine, char *outStr) { //&& (strIndex2 != 0) && (strIndex1 < strIndex2) ) ? strIndex1 + 1 : tmpFile; - if (strIndex2 == 0 || (strIndex1 > strIndex2)) { // not gcode file + if (strIndex2 == 0 || (strIndex1 > strIndex2)) { // not G-code file #if _LFN_UNICODE if (wcslen(beginIndex) > len) wcsncpy(outStr, beginIndex, len); @@ -503,7 +503,7 @@ void cutFileName(char *path, int len, int bytePerLine, char *outStr) { strcpy(outStr, beginIndex); #endif } - else { // gcode file + else { // G-code file if (strIndex2 - beginIndex > (len - 2)) { #if _LFN_UNICODE wcsncpy(outStr, (const WCHAR *)beginIndex, len - 3); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index d3f192e44f70..6a8333fd66df 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -159,7 +159,7 @@ void gCfgItems_init() { 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 + // Init G-code 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); @@ -238,7 +238,7 @@ void update_spi_flash() { uint8_t command_buf[512]; W25QXX.init(SPI_QUARTER_SPEED); - // read back the gcode command before erase spi flash + // read back the G-code 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)); @@ -249,7 +249,7 @@ 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 + // read back the G-code 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)); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp index d95efd862ba9..d143234fd53e 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp @@ -104,7 +104,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { sync_plan_position(); // Raise Z as if it was homed do_z_clearance(Z_POST_CLEARANCE); - watchdog_refresh(); + hal.watchdog_refresh(); draw_return_ui(); return; case ID_M_RETURN: @@ -117,7 +117,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { #else // Otherwise do a Z clearance move like after Homing do_z_clearance(Z_POST_CLEARANCE); #endif - watchdog_refresh(); + hal.watchdog_refresh(); draw_return_ui(); return; } diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index a14fa4d1dfb2..00bb9833fc72 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -160,6 +160,8 @@ #endif } + #include "../../../libs/buzzer.h" + void init_test_gpio() { endstops.init(); @@ -201,12 +203,7 @@ #endif } - void mks_test_beeper() { - WRITE(BEEPER_PIN, HIGH); - delay(100); - WRITE(BEEPER_PIN, LOW); - delay(100); - } + void mks_test_beeper() { buzzer.click(100); } #if ENABLED(SDSUPPORT) @@ -714,12 +711,16 @@ void disp_assets_update() { } void disp_assets_update_progress(FSTR_P const fmsg) { - static constexpr int buflen = 30; - char buf[buflen]; - memset(buf, ' ', buflen); - strncpy_P(buf, FTOP(fmsg), buflen - 1); - buf[buflen - 1] = '\0'; - disp_string(100, 165, buf, 0xFFFF, 0x0000); + #ifdef __AVR__ + static constexpr int buflen = 30; + char buf[buflen]; + memset(buf, ' ', buflen); + strncpy_P(buf, FTOP(fmsg), buflen - 1); + buf[buflen - 1] = '\0'; + disp_string(100, 165, buf, 0xFFFF, 0x0000); + #else + disp_string(100, 165, FTOP(fmsg), 0xFFFF, 0x0000); + #endif } #if BOTH(MKS_TEST, SDSUPPORT) diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index ba2df10ecbd9..c618127980bb 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -267,12 +267,12 @@ void spiFlashErase_PIC() { W25QXX.init(SPI_QUARTER_SPEED); // erase 0x001000 -64K for (pic_sectorcnt = 0; pic_sectorcnt < (64 - 4) / 4; pic_sectorcnt++) { - watchdog_refresh(); + hal.watchdog_refresh(); W25QXX.SPI_FLASH_SectorErase(PICINFOADDR + pic_sectorcnt * 4 * 1024); } // erase 64K -- 6M for (pic_sectorcnt = 0; pic_sectorcnt < (PIC_SIZE_xM * 1024 / 64 - 1); pic_sectorcnt++) { - watchdog_refresh(); + hal.watchdog_refresh(); W25QXX.SPI_FLASH_BlockErase((pic_sectorcnt + 1) * 64 * 1024); } } @@ -282,7 +282,7 @@ void spiFlashErase_PIC() { volatile uint32_t Font_sectorcnt = 0; W25QXX.init(SPI_QUARTER_SPEED); for (Font_sectorcnt = 0; Font_sectorcnt < 32 - 1; Font_sectorcnt++) { - watchdog_refresh(); + hal.watchdog_refresh(); W25QXX.SPI_FLASH_BlockErase(FONTINFOADDR + Font_sectorcnt * 64 * 1024); } } @@ -414,7 +414,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { return; } - watchdog_refresh(); + hal.watchdog_refresh(); disp_assets_update_progress(fn); W25QXX.init(SPI_QUARTER_SPEED); @@ -427,21 +427,21 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { totalSizeLoaded += pfileSize; if (assetType == ASSET_TYPE_LOGO) { do { - watchdog_refresh(); + hal.watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); Pic_Logo_Write((uint8_t*)fn, public_buf, pbr); } while (pbr >= BMP_WRITE_BUF_LEN); } else if (assetType == ASSET_TYPE_TITLE_LOGO) { do { - watchdog_refresh(); + hal.watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); Pic_TitleLogo_Write((uint8_t*)fn, public_buf, pbr); } while (pbr >= BMP_WRITE_BUF_LEN); } else if (assetType == ASSET_TYPE_G_PREVIEW) { do { - watchdog_refresh(); + hal.watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); default_view_Write(public_buf, pbr); } while (pbr >= BMP_WRITE_BUF_LEN); @@ -451,7 +451,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { SPIFlash.beginWrite(Pic_Write_Addr); #if HAS_SPI_FLASH_COMPRESSION do { - watchdog_refresh(); + hal.watchdog_refresh(); pbr = file.read(public_buf, SPI_FLASH_PageSize); TERN_(MARLIN_DEV_MODE, totalSizes += pbr); SPIFlash.writeData(public_buf, SPI_FLASH_PageSize); @@ -472,7 +472,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { else if (assetType == ASSET_TYPE_FONT) { Pic_Write_Addr = UNIGBK_FLASH_ADDR; do { - watchdog_refresh(); + hal.watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); W25QXX.SPI_FLASH_BufferWrite(public_buf, Pic_Write_Addr, pbr); Pic_Write_Addr += pbr; @@ -493,11 +493,11 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { disp_assets_update(); disp_assets_update_progress(F("Erasing pics...")); - watchdog_refresh(); + hal.watchdog_refresh(); spiFlashErase_PIC(); #if HAS_SPI_FLASH_FONT disp_assets_update_progress(F("Erasing fonts...")); - watchdog_refresh(); + hal.watchdog_refresh(); spiFlashErase_FONT(); #endif diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.h b/Marlin/src/lcd/extui/mks_ui/pic_manager.h index 320cb20b0b8d..cdcc5b76b8a9 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.h +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.h @@ -122,7 +122,7 @@ #define VAR_INF_ADDR 0x000000 #define FLASH_INF_VALID_FLAG 0x20201118 -// Store some gcode commands, such as auto leveling commands +// Store some G-code commands, such as auto-leveling commands #define GCODE_COMMAND_ADDR VAR_INF_ADDR + 3 * 1024 #define AUTO_LEVELING_COMMAND_ADDR GCODE_COMMAND_ADDR #define OTHERS_COMMAND_ADDR_1 AUTO_LEVELING_COMMAND_ADDR + 100 diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 6e852a748703..38612358110b 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -125,38 +125,37 @@ void tft_lvgl_init() { ui_cfg_init(); disp_language_init(); - watchdog_refresh(); // LVGL init takes time + hal.watchdog_refresh(); // LVGL init takes time // Init TFT first! SPI_TFT.spi_init(SPI_FULL_SPEED); SPI_TFT.LCD_init(); - watchdog_refresh(); // LVGL init takes time + hal.watchdog_refresh(); // LVGL init takes time #if ENABLED(USB_FLASH_DRIVE_SUPPORT) uint16_t usb_flash_loop = 1000; #if ENABLED(MULTI_VOLUME) && !HAS_SD_HOST_DRIVE SET_INPUT_PULLUP(SD_DETECT_PIN); - if (READ(SD_DETECT_PIN) == LOW) card.changeMedia(&card.media_driver_sdcard); - else card.changeMedia(&card.media_driver_usbFlash); + card.changeMedia(IS_SD_INSERTED() ? &card.media_driver_sdcard : &card.media_driver_usbFlash); #endif do { card.media_driver_usbFlash.idle(); - watchdog_refresh(); + hal.watchdog_refresh(); delay(2); } while (!card.media_driver_usbFlash.isInserted() && usb_flash_loop--); card.mount(); #elif HAS_LOGO_IN_FLASH delay(1000); - watchdog_refresh(); + hal.watchdog_refresh(); delay(1000); #endif - watchdog_refresh(); // LVGL init takes time + hal.watchdog_refresh(); // LVGL init takes time #if ENABLED(SDSUPPORT) UpdateAssets(); - watchdog_refresh(); // LVGL init takes time + hal.watchdog_refresh(); // LVGL init takes time TERN_(MKS_TEST, mks_test_get()); #endif diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index df90321c895d..23a39aabc469 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -123,7 +123,7 @@ uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick) { void wifi_delay(int n) { const uint32_t start = getWifiTick(); while (getWifiTickDiff(start, getWifiTick()) < (uint32_t)n) - watchdog_refresh(); + hal.watchdog_refresh(); } void wifi_reset() { @@ -1638,7 +1638,7 @@ void esp_data_parser(char *cmdRxBuf, int len) { esp_msg_index += cpyLen; - leftLen = leftLen - cpyLen; + leftLen -= cpyLen; tail_pos = charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL); if (tail_pos == -1) { @@ -1882,7 +1882,7 @@ void wifi_rcv_handle() { void wifi_looping() { do { wifi_rcv_handle(); - watchdog_refresh(); + hal.watchdog_refresh(); } while (wifi_link_state == WIFI_TRANS_FILE); } @@ -1897,7 +1897,7 @@ void mks_esp_wifi_init() { esp_state = TRANSFER_IDLE; esp_port_begin(1); - watchdog_refresh(); + hal.watchdog_refresh(); wifi_reset(); #if 0 @@ -1950,14 +1950,14 @@ void mks_esp_wifi_init() { } void mks_wifi_firmware_update() { - watchdog_refresh(); + hal.watchdog_refresh(); card.openFileRead((char *)ESP_FIRMWARE_FILE); if (card.isFileOpen()) { card.closefile(); wifi_delay(2000); - watchdog_refresh(); + hal.watchdog_refresh(); if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) return; clear_cur_ui(); @@ -1965,7 +1965,7 @@ void mks_wifi_firmware_update() { lv_draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMWARE); lv_task_handler(); - watchdog_refresh(); + hal.watchdog_refresh(); if (wifi_upload(0) >= 0) { card.removeFile((char *)ESP_FIRMWARE_FILE_RENAME); diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index 675e0eb666d2..c07cc47a3689 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -265,7 +265,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t EspUploadResult stat; //IWDG_ReloadCounter(); - watchdog_refresh(); + hal.watchdog_refresh(); if (getWifiTickDiff(startTime, getWifiTick()) > msTimeout) return timeout; @@ -445,7 +445,7 @@ EspUploadResult Sync(uint16_t timeout) { for (;;) { size_t bodyLen; EspUploadResult rc = readPacket(ESP_SYNC, 0, &bodyLen, defaultTimeout); - watchdog_refresh(); + hal.watchdog_refresh(); if (rc != success || bodyLen != 2) break; } } @@ -673,7 +673,7 @@ int32_t wifi_upload(int type) { while (esp_upload.state != upload_idle) { upload_spin(); - watchdog_refresh(); + hal.watchdog_refresh(); } ResetWiFiForUpload(1); diff --git a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp index da54fac38349..0e84fd33cf4f 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp @@ -35,25 +35,25 @@ namespace ExtUI { - void onStartup() { nextion.Startup(); } - void onIdle() { nextion.IdleLoop(); } + void onStartup() { nextion.Startup(); } + void onIdle() { nextion.IdleLoop(); } void onPrinterKilled(FSTR_P const error, FSTR_P const component) { nextion.PrinterKilled(error, component); } void onMediaInserted() {} - void onMediaError() {} - void onMediaRemoved() {} + void onMediaError() {} + void onMediaRemoved() {} void onPlayTone(const uint16_t frequency, const uint16_t duration) {} void onPrintTimerStarted() {} - void onPrintTimerPaused() {} + void onPrintTimerPaused() {} void onPrintTimerStopped() {} - void onFilamentRunout(const extruder_t) {} + void onFilamentRunout(const extruder_t) {} void onUserConfirmRequired(const char * const msg) { nextion.ConfirmationRequest(msg); } - void onStatusChanged(const char * const msg) { nextion.StatusChange(msg); } + void onStatusChanged(const char * const msg) { nextion.StatusChange(msg); } - void onHomingStart() {} + void onHomingStart() {} void onHomingDone() {} - void onPrintDone() { nextion.PrintFinished(); } + void onPrintDone() { nextion.PrintFinished(); } - void onFactoryReset() {} + void onFactoryReset() {} void onStoreSettings(char *buff) { // Called when saving to EEPROM (i.e. M500). If the ExtUI needs @@ -61,7 +61,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)); } @@ -71,7 +71,7 @@ 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)); } @@ -97,7 +97,7 @@ namespace ExtUI { // 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 diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 5d25be938c8a..57822279c530 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -169,7 +169,7 @@ namespace ExtUI { } void yield() { - if (!flags.printer_killed) thermalManager.manage_heater(); + if (!flags.printer_killed) thermalManager.task(); } void enableHeater(const extruder_t extruder) { @@ -919,11 +919,11 @@ namespace ExtUI { #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); } + bed_mesh_t& getMeshArray() { return bedlevel.z_values; } + float getMeshPoint(const xy_uint8_t &pos) { return bedlevel.z_values[pos.x][pos.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; + bedlevel.z_values[pos.x][pos.y] = zoff; TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); } } @@ -936,12 +936,10 @@ namespace ExtUI { 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; + destination.set(current_position.x, current_position.y, Z_CLEARANCE_BETWEEN_PROBES); prepare_line_to_destination(); feedrate_mm_s = XY_PROBE_FEEDRATE; - destination.x = x_target; - destination.y = y_target; + destination.set(x_target, y_target); prepare_line_to_destination(); } feedrate_mm_s = Z_PROBE_FEEDRATE_FAST; @@ -1114,15 +1112,23 @@ namespace ExtUI { // Simplest approach is to make an SRAM copy void onUserConfirmRequired(FSTR_P const fstr) { - char msg[strlen_P(FTOP(fstr)) + 1]; - strcpy_P(msg, FTOP(fstr)); - onUserConfirmRequired(msg); + #ifdef __AVR__ + char msg[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(msg, FTOP(fstr)); + onUserConfirmRequired(msg); + #else + onUserConfirmRequired(FTOP(fstr)); + #endif } void onStatusChanged(FSTR_P const fstr) { - char msg[strlen_P(FTOP(fstr)) + 1]; - strcpy_P(msg, FTOP(fstr)); - onStatusChanged(msg); + #ifdef __AVR__ + char msg[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(msg, FTOP(fstr)); + onStatusChanged(msg); + #else + onStatusChanged(FTOP(fstr)); + #endif } FileList::FileList() { refresh(); } diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 84555187677a..933f6a568ee4 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -199,7 +199,7 @@ namespace ExtUI { #endif inline void simulateUserClick() { - #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) + #if EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI) ui.lcd_clicked = true; #endif } diff --git a/Marlin/src/lcd/fontutils.cpp b/Marlin/src/lcd/fontutils.cpp index 50b671ea33a5..46329fd4be62 100644 --- a/Marlin/src/lcd/fontutils.cpp +++ b/Marlin/src/lcd/fontutils.cpp @@ -31,8 +31,6 @@ #include "../inc/MarlinConfig.h" -#define MAX_UTF8_CHAR_SIZE 4 - #if HAS_WIRED_LCD #include "marlinui.h" #include "../MarlinCore.h" @@ -40,13 +38,8 @@ #include "fontutils.h" -uint8_t read_byte_ram(uint8_t * str) { - return *str; -} - -uint8_t read_byte_rom(uint8_t * str) { - return pgm_read_byte(str); -} +uint8_t read_byte_ram(const uint8_t *str) { return *str; } +uint8_t read_byte_rom(const uint8_t *str) { return pgm_read_byte(str); } /** * @brief Using binary search to find the position by data_pin @@ -104,9 +97,9 @@ static inline bool utf8_is_start_byte_of_char(const uint8_t b) { /* 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) { +const uint8_t* get_utf8_value_cb(const uint8_t *pstart, read_byte_cb_t cb_read_byte, lchar_t &pval) { uint32_t val = 0; - uint8_t *p = pstart; + const uint8_t *p = pstart; #define NEXT_6_BITS() do{ val <<= 6; p++; valcur = cb_read_byte(p); val |= (valcur & 0x3F); }while(0) @@ -163,7 +156,7 @@ uint8_t* get_utf8_value_cb(uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t else for (; 0xFC < (0xFE & valcur); ) { p++; valcur = cb_read_byte(p); } - if (pval) *pval = val; + pval = val; return p; } diff --git a/Marlin/src/lcd/fontutils.h b/Marlin/src/lcd/fontutils.h index 21aee1e93919..69edf1a0c839 100644 --- a/Marlin/src/lcd/fontutils.h +++ b/Marlin/src/lcd/fontutils.h @@ -31,34 +31,43 @@ #pragma once #include -#include // wchar_t #include // uint32_t #include "../HAL/shared/Marduino.h" #include "../core/macros.h" -// read a byte from ROM or RAM -typedef uint8_t (*read_byte_cb_t)(uint8_t * str); +#define MAX_UTF8_CHAR_SIZE 4 + +// Use a longer character type (if needed) because wchar_t is only 16 bits wide +#ifdef MAX_UTF8_CHAR_SIZE + #if MAX_UTF8_CHAR_SIZE > 2 + typedef uint32_t lchar_t; + #else + typedef wchar_t lchar_t; + #endif +#else + #define wchar_t uint32_t +#endif -uint8_t read_byte_ram(uint8_t * str); -uint8_t read_byte_rom(uint8_t * str); +// read a byte from ROM or RAM +typedef uint8_t (*read_byte_cb_t)(const uint8_t * str); -// there's overflow of the wchar_t due to the 2-byte size in Arduino -// sizeof(wchar_t)=2; sizeof(size_t)=2; sizeof(uint32_t)=4; -// sizeof(int)=2; sizeof(long)=4; sizeof(unsigned)=2; -//#undef wchar_t -#define wchar_t uint32_t -//typedef uint32_t wchar_t; +uint8_t read_byte_ram(const uint8_t *str); +uint8_t read_byte_rom(const uint8_t *str); typedef uint16_t pixel_len_t; #define PIXEL_LEN_NOLIMIT ((pixel_len_t)(-1)) /* Perform binary search */ -typedef int (* pf_bsearch_cb_comp_t)(void *userdata, size_t idx, void * data_pin); /*"data_list[idx] - *data_pin"*/ +typedef int (* pf_bsearch_cb_comp_t)(void *userdata, size_t idx, void * data_pin); int pf_bsearch_r(void *userdata, size_t num_data, pf_bsearch_cb_comp_t cb_comp, void *data_pinpoint, size_t *ret_idx); /* Get the character, decoding multibyte UTF8 characters and returning a pointer to the start of the next UTF8 character */ -uint8_t* get_utf8_value_cb(uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t *pval); +const uint8_t* get_utf8_value_cb(const uint8_t *pstart, read_byte_cb_t cb_read_byte, lchar_t &pval); + +inline const char* get_utf8_value_cb(const char *pstart, read_byte_cb_t cb_read_byte, lchar_t &pval) { + return (const char *)get_utf8_value_cb((const uint8_t *)pstart, cb_read_byte, pval); +} /* Returns length of string in CHARACTERS, NOT BYTES */ uint8_t utf8_strlen(const char *pstart); diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 1ebe13868717..98f3d4ed97e1 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -55,7 +55,6 @@ namespace Language_an { LSTR MSG_LEVEL_BED_DONE = _UxGT("Nivelacion feita!"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Achustar desfases"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicau"); - LSTR MSG_SET_ORIGIN = _UxGT("Establir orichen"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Precalentar ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Precalentar ") PREHEAT_1_LABEL " ~"; @@ -86,7 +85,7 @@ namespace Language_an { LSTR MSG_MOVE_Z = _UxGT("Mover Z"); LSTR MSG_MOVE_E = _UxGT("Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); - LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover $mm"); LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); @@ -110,10 +109,8 @@ namespace Language_an { LSTR MSG_AMAX_A = _UxGT("Acel. max ") STR_A; LSTR MSG_AMAX_B = _UxGT("Acel. max ") STR_B; LSTR MSG_AMAX_C = _UxGT("Acel. max ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Acel. max ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Acel. max ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Acel. max ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Acel. max ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Acel. max @"); + LSTR MSG_AMAX_E = _UxGT("Acel. max E"); LSTR MSG_AMAX_EN = _UxGT("Acel. max *"); LSTR MSG_A_RETRACT = _UxGT("Acel. retrac."); LSTR MSG_A_TRAVEL = _UxGT("Acel. Viaje"); @@ -121,9 +118,7 @@ namespace Language_an { LSTR MSG_A_STEPS = STR_A _UxGT(" trangos/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" trangos/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" trangos/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" trangos/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" trangos/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" trangos/mm"); + LSTR MSG_N_STEPS = _UxGT("@ trangos/mm"); LSTR MSG_E_STEPS = _UxGT("E trangos/mm"); LSTR MSG_EN_STEPS = _UxGT("* trangos/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -169,6 +164,7 @@ namespace Language_an { LSTR MSG_BABYSTEP_X = _UxGT("Micropaso X"); LSTR MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Micropaso @"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Cancelado - Endstop"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Error: en calentar"); LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Error: temperatura"); diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 3137228c2d29..2596d62564e6 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -44,7 +44,6 @@ namespace Language_bg { LSTR MSG_DISABLE_STEPPERS = _UxGT("Изкл. двигатели"); LSTR MSG_AUTO_HOME = _UxGT("Паркиране"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Задай Начало"); - LSTR MSG_SET_ORIGIN = _UxGT("Изходна точка"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Подгряване ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Подгряване ") PREHEAT_1_LABEL " ~"; @@ -75,7 +74,7 @@ namespace Language_bg { LSTR MSG_MOVE_Z = _UxGT("Движение по Z"); LSTR MSG_MOVE_E = _UxGT("Екструдер"); LSTR MSG_MOVE_EN = _UxGT("Екструдер *"); - LSTR MSG_MOVE_N_MM = _UxGT("Премести с %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Премести с $mm"); LSTR MSG_MOVE_01MM = _UxGT("Премести с 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Премести с 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Премести с 10mm"); @@ -102,9 +101,7 @@ namespace Language_bg { LSTR MSG_A_STEPS = STR_A _UxGT(" стъпки/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" стъпки/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" стъпки/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" стъпки/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" стъпки/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" стъпки/mm"); + LSTR MSG_N_STEPS = _UxGT("@ стъпки/mm"); LSTR MSG_E_STEPS = _UxGT("E стъпки/mm"); LSTR MSG_EN_STEPS = _UxGT("* стъпки/mm"); LSTR MSG_TEMPERATURE = _UxGT("Температура"); @@ -149,6 +146,7 @@ namespace Language_bg { LSTR MSG_BABYSTEP_X = _UxGT("Министъпка X"); LSTR MSG_BABYSTEP_Y = _UxGT("Министъпка Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Министъпка Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Министъпка @"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Стоп Кр.Изключватели"); LSTR MSG_DELTA_CALIBRATE = _UxGT("Делта Калибровка"); LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Калибровка X"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 0e16c1a1fa47..fd46bcc28fc0 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -53,7 +53,6 @@ namespace Language_ca { LSTR MSG_LEVEL_BED_DONE = _UxGT("Anivellament fet!"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ajusta decalatge"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Decalatge aplicat"); - LSTR MSG_SET_ORIGIN = _UxGT("Estableix origen"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Preescalfa ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Preescalfa ") PREHEAT_1_LABEL " ~"; @@ -86,7 +85,7 @@ namespace Language_ca { LSTR MSG_MOVE_Z = _UxGT("Mou Z"); LSTR MSG_MOVE_E = _UxGT("Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); - LSTR MSG_MOVE_N_MM = _UxGT("Mou %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Mou $mm"); LSTR MSG_MOVE_01MM = _UxGT("Mou 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Mou 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Mou 10mm"); @@ -108,11 +107,9 @@ namespace Language_ca { LSTR MSG_A_STEPS = STR_A _UxGT(" passos/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" passos/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" passos/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" passos/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" passos/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" passos/mm"); - LSTR MSG_E_STEPS = _UxGT("Epassos/mm"); - LSTR MSG_EN_STEPS = _UxGT("*passos/mm"); + LSTR MSG_E_STEPS = _UxGT("@ passos/mm"); + LSTR MSG_N_STEPS = _UxGT("E passos/mm"); + LSTR MSG_EN_STEPS = _UxGT("* passos/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); LSTR MSG_MOTION = _UxGT("Moviment"); LSTR MSG_FILAMENT = _UxGT("Filament"); @@ -157,6 +154,7 @@ namespace Language_ca { LSTR MSG_BABYSTEP_X = _UxGT("Micropas X"); LSTR MSG_BABYSTEP_Y = _UxGT("Micropas Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Micropas Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Micropas @"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Cancel. Endstop"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Error al escalfar"); LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP REDUNDANT"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 6f5d8445af82..555fec1d20a2 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -77,7 +77,6 @@ namespace Language_cz { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Výška srovnávání"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Nastavit ofsety"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastaveny"); - LSTR MSG_SET_ORIGIN = _UxGT("Nastavit počátek"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Zahřát ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Zahřát ") PREHEAT_1_LABEL " ~"; @@ -236,7 +235,7 @@ namespace Language_cz { LSTR MSG_MOVE_E = _UxGT("Extrudér"); LSTR MSG_MOVE_EN = _UxGT("Extrudér *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); - LSTR MSG_MOVE_N_MM = _UxGT("Posunout o %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Posunout o $mm"); LSTR MSG_MOVE_01MM = _UxGT("Posunout o 0,1mm"); LSTR MSG_MOVE_1MM = _UxGT("Posunout o 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Posunout o 10mm"); @@ -270,19 +269,15 @@ namespace Language_cz { LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); + LSTR MSG_VN_JERK = _UxGT("Max @ Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Odchylka spoje"); - LSTR MSG_VELOCITY = _UxGT("Rychlost"); + LSTR MSG_MAX_SPEED = _UxGT("Max Rychlost"); LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Rychlost"); LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Rychlost"); LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Rychlost"); - LSTR MSG_VMAX_I = _UxGT("Max ") STR_I _UxGT(" Rychlost"); - LSTR MSG_VMAX_J = _UxGT("Max ") STR_J _UxGT(" Rychlost"); - LSTR MSG_VMAX_K = _UxGT("Max ") STR_K _UxGT(" Rychlost"); - LSTR MSG_VMAX_E = _UxGT("Max ") STR_E _UxGT(" Rychlost"); + LSTR MSG_VMAX_N = _UxGT("Max @ Rychlost"); + LSTR MSG_VMAX_E = _UxGT("Max E Rychlost"); LSTR MSG_VMAX_EN = _UxGT("Max * Rychlost"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); @@ -290,10 +285,8 @@ namespace Language_cz { LSTR MSG_AMAX_A = _UxGT("Max ") STR_A _UxGT(" Akcel"); LSTR MSG_AMAX_B = _UxGT("Max ") STR_B _UxGT(" Akcel"); LSTR MSG_AMAX_C = _UxGT("Max ") STR_C _UxGT(" Akcel"); - LSTR MSG_AMAX_I = _UxGT("Max ") STR_I _UxGT(" Akcel"); - LSTR MSG_AMAX_J = _UxGT("Max ") STR_J _UxGT(" Akcel"); - LSTR MSG_AMAX_K = _UxGT("Max ") STR_K _UxGT(" Akcel"); - LSTR MSG_AMAX_E = _UxGT("Max ") STR_E _UxGT(" Akcel"); + LSTR MSG_AMAX_N = _UxGT("Max @ Akcel"); + LSTR MSG_AMAX_E = _UxGT("Max E Akcel"); LSTR MSG_AMAX_EN = _UxGT("Max * Akcel"); LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); LSTR MSG_A_TRAVEL = _UxGT("A-přejezd"); @@ -301,9 +294,7 @@ namespace Language_cz { LSTR MSG_A_STEPS = STR_A _UxGT(" kroků/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" kroků/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" kroků/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" kroků/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" kroků/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" kroků/mm"); + LSTR MSG_N_STEPS = _UxGT("@ kroků/mm"); LSTR MSG_E_STEPS = _UxGT("E kroků/mm"); LSTR MSG_EN_STEPS = _UxGT("* kroků/mm"); LSTR MSG_TEMPERATURE = _UxGT("Teplota"); @@ -408,6 +399,7 @@ namespace Language_cz { LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Babystep @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Celkem"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop abort"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Chyba zahřívání"); @@ -440,8 +432,6 @@ namespace Language_cz { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrovat Střed"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta nastavení"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autokalibrace"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Nast.výšku delty"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Nast. Z-ofset"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag rameno"); LSTR MSG_DELTA_HEIGHT = _UxGT("Výška"); LSTR MSG_DELTA_RADIUS = _UxGT("Poloměr"); @@ -483,13 +473,7 @@ namespace Language_cz { LSTR MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); LSTR MSG_INFO_PSU = _UxGT("Nap. zdroj"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Buzení motorů"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Motor %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Motor %"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC uložit EEPROM"); LSTR MSG_ERROR_TMC = _UxGT("TMC CHYBA SPOJENÍ"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("VÝMĚNA FILAMENTU"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index b022720b5cae..05474744d0ac 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -47,7 +47,6 @@ namespace Language_da { LSTR MSG_LEVEL_BED_DONE = _UxGT("Bed level er færdig!"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Sæt forsk. af home"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Forsk. er nu aktiv"); - LSTR MSG_SET_ORIGIN = _UxGT("Sæt origin"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Forvarm ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Forvarm ") PREHEAT_1_LABEL " ~"; @@ -75,7 +74,7 @@ namespace Language_da { LSTR MSG_MOVE_X = _UxGT("Flyt X"); LSTR MSG_MOVE_Y = _UxGT("Flyt Y"); LSTR MSG_MOVE_Z = _UxGT("Flyt Z"); - LSTR MSG_MOVE_N_MM = _UxGT("Flyt %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Flyt $mm"); LSTR MSG_MOVE_01MM = _UxGT("Flyt 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Flyt 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Flyt 10mm"); @@ -173,13 +172,7 @@ namespace Language_da { LSTR MSG_INFO_PSU = _UxGT("Strømfors."); LSTR MSG_DRIVE_STRENGTH = _UxGT("Driv Styrke"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Driv %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Driv %"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 49d30f2ef6fb..a9fa16c77cbe 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -84,14 +84,7 @@ namespace Language_de { LSTR MSG_HOME_OFFSET_X = _UxGT("Homeversatz X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Homeversatz Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Homeversatz Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Homeversatz ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Homeversatz ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Homeversatz ") STR_K; - LSTR MSG_HOME_OFFSET_U = _UxGT("Homeversatz ") STR_U; - LSTR MSG_HOME_OFFSET_V = _UxGT("Homeversatz ") STR_V; - LSTR MSG_HOME_OFFSET_W = _UxGT("Homeversatz ") STR_W; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Homeversatz aktiv"); - LSTR MSG_SET_ORIGIN = _UxGT("Setze Nullpunkte"); //"G92 X0 Y0 Z0" commented out in marlinui.cpp LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Assistent"); LSTR MSG_SELECT_ORIGIN = _UxGT("Wählen Sie Ursprung"); LSTR MSG_LAST_VALUE_SP = _UxGT("Letzter Wert "); @@ -274,13 +267,11 @@ namespace Language_de { LSTR MSG_MOVE_X = _UxGT("Bewege X"); LSTR MSG_MOVE_Y = _UxGT("Bewege Y"); LSTR MSG_MOVE_Z = _UxGT("Bewege Z"); - LSTR MSG_MOVE_I = _UxGT("Bewege ") STR_I; - LSTR MSG_MOVE_J = _UxGT("Bewege ") STR_J; - LSTR MSG_MOVE_K = _UxGT("Bewege ") STR_K; + LSTR MSG_MOVE_N = _UxGT("Bewege @"); LSTR MSG_MOVE_E = _UxGT("Bewege Extruder"); LSTR MSG_MOVE_EN = _UxGT("Bewege Extruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend zu kalt"); - LSTR MSG_MOVE_N_MM = _UxGT(" %s mm"); + LSTR MSG_MOVE_N_MM = _UxGT(" $ mm"); LSTR MSG_MOVE_01MM = _UxGT(" 0,1 mm"); LSTR MSG_MOVE_1MM = _UxGT(" 1,0 mm"); LSTR MSG_MOVE_10MM = _UxGT(" 10,0 mm"); @@ -290,12 +281,6 @@ namespace Language_de { LSTR MSG_MOVE_01IN = _UxGT("0.100 in"); LSTR MSG_MOVE_1IN = _UxGT("1.000 in"); LSTR MSG_SPEED = _UxGT("Geschw."); - LSTR MSG_MAXSPEED = _UxGT("Max Geschw. (mm/s)"); - LSTR MSG_MAXSPEED_X = _UxGT("Max ") STR_A _UxGT(" Geschw."); - LSTR MSG_MAXSPEED_Y = _UxGT("Max ") STR_B _UxGT(" Geschw."); - LSTR MSG_MAXSPEED_Z = _UxGT("Max ") STR_C _UxGT(" Geschw."); - LSTR MSG_MAXSPEED_E = _UxGT("Max ") STR_E _UxGT(" Geschw."); - LSTR MSG_MAXSPEED_A = _UxGT("Max @ Geschw."); LSTR MSG_BED_Z = _UxGT("Bett Z"); LSTR MSG_NOZZLE = _UxGT("Düse"); LSTR MSG_NOZZLE_N = _UxGT("Düse ~"); @@ -330,8 +315,8 @@ namespace Language_de { LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); LSTR MSG_PID_CYCLE = _UxGT("PID Zyklus"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID Tuning fertig"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge. Falscher Extruder"); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge. Temperatur zu hoch."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge.! Falscher Extruder"); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge.! Temperatur zu hoch."); LSTR MSG_PID_TIMEOUT = _UxGT("Autotune fehlge.! Timeout."); LSTR MSG_MPC_MEASURING_AMBIENT = _UxGT("teste Wärmeverlust"); LSTR MSG_MPC_AUTOTUNE = _UxGT("Autotune MPC"); @@ -348,19 +333,15 @@ namespace Language_de { LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); + LSTR MSG_VN_JERK = _UxGT("Max @ Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); - LSTR MSG_VELOCITY = _UxGT("Geschwindigkeit"); + LSTR MSG_MAX_SPEED = _UxGT("Max Geschw. (mm/s)"); LSTR MSG_VMAX_A = _UxGT("V max ") STR_A; LSTR MSG_VMAX_B = _UxGT("V max ") STR_B; LSTR MSG_VMAX_C = _UxGT("V max ") STR_C; - LSTR MSG_VMAX_I = _UxGT("V max ") STR_I; - LSTR MSG_VMAX_J = _UxGT("V max ") STR_J; - LSTR MSG_VMAX_K = _UxGT("V max ") STR_K; - LSTR MSG_VMAX_E = _UxGT("V max ") STR_E; + LSTR MSG_VMAX_N = _UxGT("V max @"); + LSTR MSG_VMAX_E = _UxGT("V max E"); LSTR MSG_VMAX_EN = _UxGT("V max *"); LSTR MSG_VMIN = _UxGT("V min "); LSTR MSG_VTRAV_MIN = _UxGT("V min Leerfahrt"); @@ -368,10 +349,8 @@ namespace Language_de { LSTR MSG_AMAX_A = _UxGT("A max ") STR_A; LSTR MSG_AMAX_B = _UxGT("A max ") STR_B; LSTR MSG_AMAX_C = _UxGT("A max ") STR_C; - LSTR MSG_AMAX_I = _UxGT("A max ") STR_I; - LSTR MSG_AMAX_J = _UxGT("A max ") STR_J; - LSTR MSG_AMAX_K = _UxGT("A max ") STR_K; - LSTR MSG_AMAX_E = _UxGT("A max ") STR_E; + LSTR MSG_AMAX_N = _UxGT("A max @"); + LSTR MSG_AMAX_E = _UxGT("A max E"); LSTR MSG_AMAX_EN = _UxGT("A max *"); LSTR MSG_A_RETRACT = _UxGT("A Einzug"); LSTR MSG_A_TRAVEL = _UxGT("A Leerfahrt"); @@ -381,10 +360,8 @@ namespace Language_de { LSTR MSG_A_STEPS = STR_A _UxGT(" Steps/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" Steps/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" Steps/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" Steps/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" Steps/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" Steps/mm"); - LSTR MSG_E_STEPS = STR_E _UxGT(" Steps/mm"); + LSTR MSG_N_STEPS = _UxGT("@ Steps/mm"); + LSTR MSG_E_STEPS = _UxGT("E Steps/mm"); LSTR MSG_EN_STEPS = _UxGT("* Steps/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatur"); LSTR MSG_MOTION = _UxGT("Bewegung"); @@ -534,9 +511,7 @@ namespace Language_de { LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; + LSTR MSG_BABYSTEP_N = _UxGT("Babystep @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Abbr. mit Endstopp"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("HEIZEN ERFOLGLOS"); @@ -569,8 +544,6 @@ namespace Language_de { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibriere Mitte"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Einst. anzeig."); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autom. Kalibrierung"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Höhe setzen"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Sondenversatz Z"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); LSTR MSG_DELTA_HEIGHT = _UxGT("Höhe"); LSTR MSG_DELTA_RADIUS = _UxGT("Radius"); @@ -630,13 +603,7 @@ namespace Language_de { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); LSTR MSG_INFO_PSU = _UxGT("Netzteil"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Motorleistung"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Treiber %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Treiber %"); LSTR MSG_ERROR_TMC = _UxGT("TMC Verbindungsfehler"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Werte speichern"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMENT WECHSEL"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index f3cd7ef27898..47d6a5b2da35 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -64,7 +64,6 @@ namespace Language_el { LSTR MSG_LEVEL_BED_DONE = _UxGT("Τέλος επιπεδοποίησης!"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ορισμός μετατοπίσεων"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Εφαρμογή μετατοπίσεων"); - LSTR MSG_SET_ORIGIN = _UxGT("Ορισμός προέλευσης"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL " ~"; @@ -120,17 +119,13 @@ namespace Language_el { LSTR MSG_VA_JERK = _UxGT("Vαντίδραση ") STR_A; LSTR MSG_VB_JERK = _UxGT("Vαντίδραση ") STR_B; LSTR MSG_VC_JERK = _UxGT("Vαντίδραση ") STR_C; - LSTR MSG_VI_JERK = _UxGT("Vαντίδραση ") STR_I; - LSTR MSG_VJ_JERK = _UxGT("Vαντίδραση ") STR_J; - LSTR MSG_VK_JERK = _UxGT("Vαντίδραση ") STR_K; + LSTR MSG_VN_JERK = _UxGT("Vαντίδραση @"); LSTR MSG_VE_JERK = _UxGT("Vαντίδραση E"); LSTR MSG_VMAX_A = _UxGT("V Μέγιστο") STR_A; LSTR MSG_VMAX_B = _UxGT("V Μέγιστο") STR_B; LSTR MSG_VMAX_C = _UxGT("V Μέγιστο") STR_C; - LSTR MSG_VMAX_I = _UxGT("V Μέγιστο") STR_I; - LSTR MSG_VMAX_J = _UxGT("V Μέγιστο") STR_J; - LSTR MSG_VMAX_K = _UxGT("V Μέγιστο") STR_K; - LSTR MSG_VMAX_E = _UxGT("V Μέγιστο") STR_E; + LSTR MSG_VMAX_N = _UxGT("V Μέγιστο@"); + LSTR MSG_VMAX_E = _UxGT("V ΜέγιστοE"); LSTR MSG_VMAX_EN = _UxGT("V Μέγιστο *"); LSTR MSG_VMIN = _UxGT("V Ελάχιστο"); LSTR MSG_VTRAV_MIN = _UxGT("Vελάχ. μετατόπιση"); @@ -138,10 +133,8 @@ namespace Language_el { LSTR MSG_AMAX_A = _UxGT("Aμεγ ") STR_A; LSTR MSG_AMAX_B = _UxGT("Aμεγ ") STR_B; LSTR MSG_AMAX_C = _UxGT("Aμεγ ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Aμεγ ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Aμεγ ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Aμεγ ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Aμεγ ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Aμεγ @"); + LSTR MSG_AMAX_E = _UxGT("Aμεγ E"); LSTR MSG_AMAX_EN = _UxGT("Aμεγ *"); LSTR MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); LSTR MSG_A_TRAVEL = _UxGT("Α-μετατόπιση"); @@ -149,9 +142,7 @@ namespace Language_el { LSTR MSG_A_STEPS = _UxGT("Bήματα ") STR_A _UxGT(" ανά μμ"); LSTR MSG_B_STEPS = _UxGT("Bήματα ") STR_B _UxGT(" ανά μμ"); LSTR MSG_C_STEPS = _UxGT("Bήματα ") STR_C _UxGT(" ανά μμ"); - LSTR MSG_I_STEPS = _UxGT("Bήματα ") STR_I _UxGT(" ανά μμ"); - LSTR MSG_J_STEPS = _UxGT("Bήματα ") STR_J _UxGT(" ανά μμ"); - LSTR MSG_K_STEPS = _UxGT("Bήματα ") STR_K _UxGT(" ανά μμ"); + LSTR MSG_N_STEPS = _UxGT("Bήματα @ ανά μμ"); LSTR MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); LSTR MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); LSTR MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index d8c7cae38d68..bd2e7d595d9a 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -53,7 +53,6 @@ namespace Language_el_gr { LSTR MSG_LEVEL_BED_DONE = _UxGT("Ολοκλήρωση επιπεδοποίησης!"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ορισμός βασικών μετατοπίσεων"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Εφαρμόστηκαν οι μετατοπίσεις"); - LSTR MSG_SET_ORIGIN = _UxGT("Ορισμός προέλευσης"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL " ~"; @@ -110,17 +109,13 @@ namespace Language_el_gr { LSTR MSG_VA_JERK = _UxGT("Vαντίδραση ") STR_A; LSTR MSG_VB_JERK = _UxGT("Vαντίδραση ") STR_B; LSTR MSG_VC_JERK = _UxGT("Vαντίδραση ") STR_C; - LSTR MSG_VI_JERK = _UxGT("Vαντίδραση ") STR_I; - LSTR MSG_VJ_JERK = _UxGT("Vαντίδραση ") STR_J; - LSTR MSG_VK_JERK = _UxGT("Vαντίδραση ") STR_K; + LSTR MSG_VN_JERK = _UxGT("Vαντίδραση @"); LSTR MSG_VE_JERK = _UxGT("Vαντίδραση E"); LSTR MSG_VMAX_A = _UxGT("Vμεγ ") STR_A; LSTR MSG_VMAX_B = _UxGT("Vμεγ ") STR_B; LSTR MSG_VMAX_C = _UxGT("Vμεγ ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Vμεγ ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Vμεγ ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Vμεγ ") STR_K; - LSTR MSG_VMAX_E = _UxGT("Vμεγ ") STR_E; + LSTR MSG_VMAX_N = _UxGT("Vμεγ @"); + LSTR MSG_VMAX_E = _UxGT("Vμεγ E"); LSTR MSG_VMAX_EN = _UxGT("Vμεγ *"); LSTR MSG_VMIN = _UxGT("Vελαχ"); LSTR MSG_VTRAV_MIN = _UxGT("Vελάχ. μετατόπιση"); @@ -128,10 +123,8 @@ namespace Language_el_gr { LSTR MSG_AMAX_A = _UxGT("Aμεγ ") STR_A; LSTR MSG_AMAX_B = _UxGT("Aμεγ ") STR_B; LSTR MSG_AMAX_C = _UxGT("Aμεγ ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Aμεγ ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Aμεγ ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Aμεγ ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Aμεγ ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Aμεγ @"); + LSTR MSG_AMAX_E = _UxGT("Aμεγ E"); LSTR MSG_AMAX_EN = _UxGT("Aμεγ *"); LSTR MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); LSTR MSG_A_TRAVEL = _UxGT("Α-μετατόπιση"); @@ -139,9 +132,7 @@ namespace Language_el_gr { LSTR MSG_A_STEPS = _UxGT("Bήματα ") STR_A _UxGT(" ανά μμ"); LSTR MSG_B_STEPS = _UxGT("Bήματα ") STR_B _UxGT(" ανά μμ"); LSTR MSG_C_STEPS = _UxGT("Bήματα ") STR_C _UxGT(" ανά μμ"); - LSTR MSG_I_STEPS = _UxGT("Bήματα ") STR_I _UxGT(" ανά μμ"); - LSTR MSG_J_STEPS = _UxGT("Bήματα ") STR_J _UxGT(" ανά μμ"); - LSTR MSG_K_STEPS = _UxGT("Bήματα ") STR_K _UxGT(" ανά μμ"); + LSTR MSG_N_STEPS = _UxGT("Bήματα @ ανά μμ"); LSTR MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); LSTR MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); LSTR MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 31c19e542e01..f2a9cb0c0868 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -27,10 +27,9 @@ * 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: + * Substitutions are applied for the following characters when used in menu items titles: * - * $ displays an inserted C-string + * $ displays an inserted string * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) @@ -53,7 +52,10 @@ namespace Language_en { LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Ready."); LSTR MSG_YES = _UxGT("YES"); LSTR MSG_NO = _UxGT("NO"); + LSTR MSG_HIGH = _UxGT("HIGH"); + LSTR MSG_LOW = _UxGT("LOW"); LSTR MSG_BACK = _UxGT("Back"); + LSTR MSG_ERROR = _UxGT("Error"); LSTR MSG_MEDIA_ABORTING = _UxGT("Aborting..."); LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_EN _UxGT(" Inserted"); LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_EN _UxGT(" Removed"); @@ -67,6 +69,8 @@ namespace Language_en { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); LSTR MSG_MAIN = _UxGT("Main"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Advanced Settings"); + LSTR MSG_TOOLBAR_SETUP = _UxGT("Toolbar Setup"); + LSTR MSG_OPTION_DISABLED = _UxGT("Option Disabled"); LSTR MSG_CONFIGURATION = _UxGT("Configuration"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Run Auto Files"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Disable Steppers"); @@ -80,6 +84,7 @@ namespace Language_en { LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); LSTR MSG_FILAMENT_SET = _UxGT("Filament Settings"); LSTR MSG_FILAMENT_MAN = _UxGT("Filament Management"); + LSTR MSG_MANUAL_LEVELING = _UxGT("Manual Leveling"); LSTR MSG_LEVBED_FL = _UxGT("Front Left"); LSTR MSG_LEVBED_FR = _UxGT("Front Right"); LSTR MSG_LEVBED_C = _UxGT("Center"); @@ -100,14 +105,7 @@ namespace Language_en { LSTR MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Home Offset ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Home Offset ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Home Offset ") STR_K; - LSTR MSG_HOME_OFFSET_U = _UxGT("Home Offset ") STR_U; - LSTR MSG_HOME_OFFSET_V = _UxGT("Home Offset ") STR_V; - LSTR MSG_HOME_OFFSET_W = _UxGT("Home Offset ") STR_W; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); - LSTR MSG_SET_ORIGIN = _UxGT("Set Origin"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); LSTR MSG_SELECT_ORIGIN = _UxGT("Select Origin"); LSTR MSG_LAST_VALUE_SP = _UxGT("Last value "); @@ -119,7 +117,14 @@ namespace Language_en { LSTR MSG_PREHEAT_1_ALL = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" All"); LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Bed"); LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Conf"); - + #ifdef PREHEAT_2_LABEL + LSTR MSG_PREHEAT_2 = _UxGT("Preheat ") PREHEAT_2_LABEL; + LSTR MSG_PREHEAT_2_SETTINGS = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Conf"); + #endif + #ifdef PREHEAT_3_LABEL + LSTR MSG_PREHEAT_3 = _UxGT("Preheat ") PREHEAT_3_LABEL; + LSTR MSG_PREHEAT_3_SETTINGS = _UxGT("Preheat ") PREHEAT_3_LABEL _UxGT(" Conf"); + #endif LSTR MSG_PREHEAT_M = _UxGT("Preheat $"); LSTR MSG_PREHEAT_M_H = _UxGT("Preheat $ ~"); LSTR MSG_PREHEAT_M_END = _UxGT("Preheat $ End"); @@ -166,10 +171,19 @@ namespace Language_en { LSTR MSG_MESH_VIEW = _UxGT("View Mesh"); LSTR MSG_EDITING_STOPPED = _UxGT("Mesh Editing Stopped"); LSTR MSG_NO_VALID_MESH = _UxGT("No valid mesh"); + LSTR MSG_ACTIVATE_MESH = _UxGT("Activate Leveling"); LSTR MSG_PROBING_POINT = _UxGT("Probing Point"); LSTR MSG_MESH_X = _UxGT("Index X"); LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_INSET = _UxGT("Mesh Inset"); + LSTR MSG_MESH_MIN_X = _UxGT("Mesh X Minimum"); + LSTR MSG_MESH_MAX_X = _UxGT("Mesh X Maximum"); + LSTR MSG_MESH_MIN_Y = _UxGT("Mesh Y Minimum"); + LSTR MSG_MESH_MAX_Y = _UxGT("Mesh Y Maximum"); + LSTR MSG_MESH_AMAX = _UxGT("Maximize Area"); + LSTR MSG_MESH_CENTER = _UxGT("Center Area"); LSTR MSG_MESH_EDIT_Z = _UxGT("Z Value"); + LSTR MSG_MESH_CANCEL = _UxGT("Mesh cancelled"); LSTR MSG_CUSTOM_COMMANDS = _UxGT("Custom Commands"); LSTR MSG_M48_TEST = _UxGT("M48 Probe Test"); LSTR MSG_M48_POINT = _UxGT("M48 Point"); @@ -188,6 +202,9 @@ namespace Language_en { LSTR MSG_UBL_TOOLS = _UxGT("UBL Tools"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Tilting Point"); + LSTR MSG_UBL_TILT_MESH = _UxGT("Tilt Mesh"); + LSTR MSG_UBL_TILTING_GRID = _UxGT("Tilting Grid Size"); + LSTR MSG_UBL_MESH_TILTED = _UxGT("Mesh Tilted"); LSTR MSG_UBL_MANUAL_MESH = _UxGT("Manually Build Mesh"); LSTR MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); LSTR MSG_UBL_BC_INSERT = _UxGT("Place Shim & Measure"); @@ -236,6 +253,7 @@ namespace Language_en { LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manual Fill-in"); LSTR MSG_UBL_SMART_FILLIN = _UxGT("Smart Fill-in"); LSTR MSG_UBL_FILLIN_MESH = _UxGT("Fill-in Mesh"); + LSTR MSG_UBL_MESH_FILLED = _UxGT("Missing Points Filled"); LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidate All"); LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidate Closest"); LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Fine Tune All"); @@ -244,6 +262,7 @@ namespace Language_en { LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Memory Slot"); LSTR MSG_UBL_LOAD_MESH = _UxGT("Load Bed Mesh"); LSTR MSG_UBL_SAVE_MESH = _UxGT("Save Bed Mesh"); + LSTR MSG_UBL_INVALID_SLOT = _UxGT("First Select a Mesh Slot"); LSTR MSG_MESH_LOADED = _UxGT("Mesh %i Loaded"); LSTR MSG_MESH_SAVED = _UxGT("Mesh %i Saved"); LSTR MSG_UBL_NO_STORAGE = _UxGT("No Storage"); @@ -288,16 +307,11 @@ namespace Language_en { LSTR MSG_MOVE_X = _UxGT("Move X"); // Used by draw_edit_screen LSTR MSG_MOVE_Y = _UxGT("Move Y"); LSTR MSG_MOVE_Z = _UxGT("Move Z"); - LSTR MSG_MOVE_I = _UxGT("Move ") STR_I; - LSTR MSG_MOVE_J = _UxGT("Move ") STR_J; - LSTR MSG_MOVE_K = _UxGT("Move ") STR_K; - LSTR MSG_MOVE_U = _UxGT("Move ") STR_U; - LSTR MSG_MOVE_V = _UxGT("Move ") STR_V; - LSTR MSG_MOVE_W = _UxGT("Move ") STR_W; + LSTR MSG_MOVE_N = _UxGT("Move @"); LSTR MSG_MOVE_E = _UxGT("Move Extruder"); - LSTR MSG_MOVE_EN = _UxGT("Move E*"); + LSTR MSG_MOVE_EN = _UxGT("Move *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold"); - LSTR MSG_MOVE_N_MM = _UxGT("Move %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Move $mm"); LSTR MSG_MOVE_01MM = _UxGT("Move 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Move 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Move 10mm"); @@ -307,12 +321,6 @@ namespace Language_en { LSTR MSG_MOVE_01IN = _UxGT("Move 0.1in"); LSTR MSG_MOVE_1IN = _UxGT("Move 1.0in"); LSTR MSG_SPEED = _UxGT("Speed"); - LSTR MSG_MAXSPEED = _UxGT("Max Speed (mm/s)"); - LSTR MSG_MAXSPEED_X = _UxGT("Max ") STR_A _UxGT(" Speed"); - LSTR MSG_MAXSPEED_Y = _UxGT("Max ") STR_B _UxGT(" Speed"); - LSTR MSG_MAXSPEED_Z = _UxGT("Max ") STR_C _UxGT(" Speed"); - LSTR MSG_MAXSPEED_E = _UxGT("Max ") STR_E _UxGT(" Speed"); - LSTR MSG_MAXSPEED_A = _UxGT("Max @ Speed"); LSTR MSG_BED_Z = _UxGT("Bed Z"); LSTR MSG_NOZZLE = _UxGT("Nozzle"); LSTR MSG_NOZZLE_N = _UxGT("Nozzle ~"); @@ -347,8 +355,12 @@ namespace Language_en { LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); LSTR MSG_PID_CYCLE = _UxGT("PID Cycles"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("PID Autotune failed!"); + LSTR MSG_BAD_EXTRUDER_NUM = _UxGT("Bad extruder."); + LSTR MSG_TEMP_TOO_HIGH = _UxGT("Temperature too high."); + LSTR MSG_TIMEOUT = _UxGT("Timeout."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed! Bad extruder."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed! Temperature too high."); LSTR MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); LSTR MSG_MPC_MEASURING_AMBIENT = _UxGT("Testing heat loss"); LSTR MSG_MPC_AUTOTUNE = _UxGT("MPC Autotune"); @@ -365,39 +377,24 @@ namespace Language_en { LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); - LSTR MSG_VU_JERK = _UxGT("Max ") STR_U _UxGT(" Jerk"); - LSTR MSG_VV_JERK = _UxGT("Max ") STR_V _UxGT(" Jerk"); - LSTR MSG_VW_JERK = _UxGT("Max ") STR_W _UxGT(" Jerk"); + LSTR MSG_VN_JERK = _UxGT("Max @ Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); - LSTR MSG_VELOCITY = _UxGT("Velocity"); - LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Vel"); - LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Vel"); - LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Vel"); - LSTR MSG_VMAX_I = _UxGT("Max ") STR_I _UxGT(" Vel"); - LSTR MSG_VMAX_J = _UxGT("Max ") STR_J _UxGT(" Vel"); - LSTR MSG_VMAX_K = _UxGT("Max ") STR_K _UxGT(" Vel"); - LSTR MSG_VMAX_U = _UxGT("Max ") STR_U _UxGT(" Vel"); - LSTR MSG_VMAX_V = _UxGT("Max ") STR_V _UxGT(" Vel"); - LSTR MSG_VMAX_W = _UxGT("Max ") STR_W _UxGT(" Vel"); - LSTR MSG_VMAX_E = _UxGT("Max ") STR_E _UxGT(" Vel"); - LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); + LSTR MSG_MAX_SPEED = _UxGT("Max Speed (mm/s)"); + LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Speed"); + LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Speed"); + LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Speed"); + LSTR MSG_VMAX_N = _UxGT("Max @ Speed"); + LSTR MSG_VMAX_E = _UxGT("Max E Speed"); + LSTR MSG_VMAX_EN = _UxGT("Max * Speed"); LSTR MSG_VMIN = _UxGT("Min Velocity"); - LSTR MSG_VTRAV_MIN = _UxGT("Min Travel Vel"); + LSTR MSG_VTRAV_MIN = _UxGT("Min Travel Speed"); LSTR MSG_ACCELERATION = _UxGT("Acceleration"); LSTR MSG_AMAX_A = _UxGT("Max ") STR_A _UxGT(" Accel"); LSTR MSG_AMAX_B = _UxGT("Max ") STR_B _UxGT(" Accel"); LSTR MSG_AMAX_C = _UxGT("Max ") STR_C _UxGT(" Accel"); - LSTR MSG_AMAX_I = _UxGT("Max ") STR_I _UxGT(" Accel"); - LSTR MSG_AMAX_J = _UxGT("Max ") STR_J _UxGT(" Accel"); - LSTR MSG_AMAX_K = _UxGT("Max ") STR_K _UxGT(" Accel"); - LSTR MSG_AMAX_U = _UxGT("Max ") STR_U _UxGT(" Accel"); - LSTR MSG_AMAX_V = _UxGT("Max ") STR_V _UxGT(" Accel"); - LSTR MSG_AMAX_W = _UxGT("Max ") STR_W _UxGT(" Accel"); - LSTR MSG_AMAX_E = _UxGT("Max ") STR_E _UxGT(" Accel"); + LSTR MSG_AMAX_N = _UxGT("Max @ Accel"); + LSTR MSG_AMAX_E = _UxGT("Max E Accel"); LSTR MSG_AMAX_EN = _UxGT("Max * Accel"); LSTR MSG_A_RETRACT = _UxGT("Retract Accel"); LSTR MSG_A_TRAVEL = _UxGT("Travel Accel"); @@ -407,12 +404,7 @@ namespace Language_en { LSTR MSG_A_STEPS = STR_A _UxGT(" Steps/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" Steps/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" Steps/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" Steps/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" Steps/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" Steps/mm"); - LSTR MSG_U_STEPS = STR_U _UxGT(" Steps/mm"); - LSTR MSG_V_STEPS = STR_V _UxGT(" Steps/mm"); - LSTR MSG_W_STEPS = STR_W _UxGT(" Steps/mm"); + LSTR MSG_N_STEPS = _UxGT("@ steps/mm"); LSTR MSG_E_STEPS = _UxGT("E steps/mm"); LSTR MSG_EN_STEPS = _UxGT("* Steps/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperature"); @@ -444,6 +436,10 @@ namespace Language_en { LSTR MSG_RESET_PRINTER = _UxGT("Reset Printer"); LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Refresh"); LSTR MSG_INFO_SCREEN = _UxGT("Info Screen"); + LSTR MSG_INFO_MACHINENAME = _UxGT("Machine Name"); + LSTR MSG_INFO_SIZE = _UxGT("Size"); + LSTR MSG_INFO_FWVERSION = _UxGT("Firmware Version"); + LSTR MSG_INFO_BUILD = _UxGT("Build Datetime"); LSTR MSG_PREPARE = _UxGT("Prepare"); LSTR MSG_TUNE = _UxGT("Tune"); LSTR MSG_POWER_MONITOR = _UxGT("Power monitor"); @@ -470,6 +466,7 @@ namespace Language_en { LSTR MSG_BUTTON_RESUME = _UxGT("Resume"); LSTR MSG_BUTTON_ADVANCED = _UxGT("Advanced"); LSTR MSG_BUTTON_SAVE = _UxGT("Save"); + LSTR MSG_BUTTON_PURGE = _UxGT("Purge"); LSTR MSG_PAUSING = _UxGT("Pausing..."); LSTR MSG_PAUSE_PRINT = _UxGT("Pause Print"); LSTR MSG_ADVANCED_PAUSE = _UxGT("Advanced Pause"); @@ -492,9 +489,12 @@ namespace Language_en { LSTR MSG_REMAINING_TIME = _UxGT("Remaining"); LSTR MSG_PRINT_ABORTED = _UxGT("Print Aborted"); LSTR MSG_PRINT_DONE = _UxGT("Print Done"); + LSTR MSG_PRINTER_KILLED = _UxGT("Printer killed!"); + LSTR MSG_TURN_OFF = _UxGT("Turn off the printer"); LSTR MSG_NO_MOVE = _UxGT("No Move."); LSTR MSG_KILLED = _UxGT("KILLED. "); LSTR MSG_STOPPED = _UxGT("STOPPED. "); + LSTR MSG_FWRETRACT = _UxGT("Firmware Retract"); LSTR MSG_CONTROL_RETRACT = _UxGT("Retract mm"); LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Re.mm"); LSTR MSG_CONTROL_RETRACTF = _UxGT("Retract V"); @@ -560,16 +560,14 @@ namespace Language_en { LSTR MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); LSTR MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Probe Z Offset"); + LSTR MSG_ZPROBE_MARGIN = _UxGT("Probe Margin"); + LSTR MSG_Z_FEED_RATE = _UxGT("Z Feed Rate"); + LSTR MSG_ENABLE_HS_MODE = _UxGT("Enable HS mode"); LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Move Nozzle to Bed"); LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; - LSTR MSG_BABYSTEP_U = _UxGT("Babystep ") STR_U; - LSTR MSG_BABYSTEP_V = _UxGT("Babystep ") STR_V; - LSTR MSG_BABYSTEP_W = _UxGT("Babystep ") STR_W; + LSTR MSG_BABYSTEP_N = _UxGT("Babystep @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); @@ -602,8 +600,6 @@ namespace Language_en { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrate Center"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Settings"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibration"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Set Delta Height"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Probe Z-offset"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); LSTR MSG_DELTA_HEIGHT = _UxGT("Height"); LSTR MSG_DELTA_RADIUS = _UxGT("Radius"); @@ -630,25 +626,28 @@ namespace Language_en { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); + LSTR MSG_COLORS_GET = _UxGT("Get Color"); + LSTR MSG_COLORS_SELECT = _UxGT("Select Colors"); + LSTR MSG_COLORS_APPLIED = _UxGT("Colors applied"); + LSTR MSG_COLORS_RED = _UxGT("Red"); + LSTR MSG_COLORS_GREEN = _UxGT("Green"); + LSTR MSG_COLORS_BLUE = _UxGT("Blue"); + LSTR MSG_COLORS_WHITE = _UxGT("White"); + LSTR MSG_UI_LANGUAGE = _UxGT("UI Language"); + LSTR MSG_SOUND_ENABLE = _UxGT("Enable sound"); + LSTR MSG_LOCKSCREEN = _UxGT("Lock Screen"); + LSTR MSG_LOCKSCREEN_LOCKED = _UxGT("Printer is Locked,"); + LSTR MSG_LOCKSCREEN_UNLOCK = _UxGT("Scroll to unlock."); + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Please wait until reboot."); + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("No media inserted."); - LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Please wait until reboot. "); LSTR MSG_PLEASE_PREHEAT = _UxGT("Please preheat the hot end."); LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Reset Print Count"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Print Count"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Print Time"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Longest Job Time"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded Total"); - LSTR MSG_COLORS_GET = _UxGT("Get Color"); - LSTR MSG_COLORS_SELECT = _UxGT("Select Colors"); - LSTR MSG_COLORS_APPLIED = _UxGT("Colors applied"); - LSTR MSG_COLORS_RED = _UxGT("Red"); - LSTR MSG_COLORS_GREEN = _UxGT("Green"); - LSTR MSG_COLORS_BLUE = _UxGT("Blue"); - LSTR MSG_COLORS_WHITE = _UxGT("White"); - LSTR MSG_UI_LANGUAGE = _UxGT("UI Language"); - LSTR MSG_SOUND_ENABLE = _UxGT("Enable sound"); - LSTR MSG_LOCKSCREEN = _UxGT("Lock Screen"); #else LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("No Media"); LSTR MSG_PLEASE_PREHEAT = _UxGT("Please Preheat"); @@ -663,16 +662,7 @@ namespace Language_en { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); LSTR MSG_INFO_PSU = _UxGT("PSU"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_U = STR_U _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_V = STR_V _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_W = STR_W _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Driver %"); LSTR MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMENT CHANGE"); @@ -682,10 +672,14 @@ namespace Language_en { LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("RESUME OPTIONS:"); LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purge more"); LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continue"); + LSTR MSG_FILAMENT_CHANGE_PURGE_CONTINUE = _UxGT("Purge or Continue?"); LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozzle: "); LSTR MSG_RUNOUT_SENSOR = _UxGT("Runout Sensor"); LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout Dist mm"); LSTR MSG_RUNOUT_ENABLE = _UxGT("Enable Runout"); + LSTR MSG_RUNOUT_ACTIVE = _UxGT("Runout Active"); + LSTR MSG_INVERT_EXTRUDER = _UxGT("Invert Extruder"); + LSTR MSG_EXTRUDER_MIN_TEMP = _UxGT("Extruder Min Temp."); LSTR MSG_FANCHECK = _UxGT("Fan Tacho Check"); LSTR MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); @@ -841,15 +835,7 @@ namespace Language_en { LSTR MSG_PID_C_E = _UxGT("PID-C *"); LSTR MSG_PID_F = _UxGT("PID-F"); LSTR MSG_PID_F_E = _UxGT("PID-F *"); - LSTR MSG_BACKLASH_A = STR_A; - LSTR MSG_BACKLASH_B = STR_B; - LSTR MSG_BACKLASH_C = STR_C; - LSTR MSG_BACKLASH_I = STR_I; - LSTR MSG_BACKLASH_J = STR_J; - LSTR MSG_BACKLASH_K = STR_K; - LSTR MSG_BACKLASH_U = STR_U; - LSTR MSG_BACKLASH_V = STR_V; - LSTR MSG_BACKLASH_W = STR_W; + LSTR MSG_BACKLASH_N = _UxGT("@"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 6e2c82533e6f..9cb86c5c3246 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -72,7 +72,6 @@ namespace Language_es { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Compen. Altura"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ajustar desfases"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicada"); - LSTR MSG_SET_ORIGIN = _UxGT("Establecer origen"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Precal. ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Precal. ") PREHEAT_1_LABEL " ~"; @@ -230,7 +229,7 @@ namespace Language_es { LSTR MSG_MOVE_E = _UxGT("Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend muy frio"); - LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover $mm"); LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); @@ -271,30 +270,24 @@ namespace Language_es { LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); + LSTR MSG_VN_JERK = _UxGT("Max @ Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desvi. Unión"); - LSTR MSG_VELOCITY = _UxGT("Velocidad"); - LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Vel"); - LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Vel"); - LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Vel"); - LSTR MSG_VMAX_I = _UxGT("Max ") STR_I _UxGT(" Vel"); - LSTR MSG_VMAX_J = _UxGT("Max ") STR_J _UxGT(" Vel"); - LSTR MSG_VMAX_K = _UxGT("Max ") STR_K _UxGT(" Vel"); - LSTR MSG_VMAX_E = _UxGT("Max ") STR_E _UxGT(" Vel"); - LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); + LSTR MSG_MAX_SPEED = _UxGT("Max Velocidad"); + LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Speed"); + LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Speed"); + LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Speed"); + LSTR MSG_VMAX_N = _UxGT("Max @ Speed"); + LSTR MSG_VMAX_E = _UxGT("Max E Speed"); + LSTR MSG_VMAX_EN = _UxGT("Max * Speed"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("Vel. viaje min"); LSTR MSG_ACCELERATION = _UxGT("Acceleración"); LSTR MSG_AMAX_A = _UxGT("Acel. max") STR_A; LSTR MSG_AMAX_B = _UxGT("Acel. max") STR_B; LSTR MSG_AMAX_C = _UxGT("Acel. max") STR_C; - LSTR MSG_AMAX_I = _UxGT("Acel. max") STR_I; - LSTR MSG_AMAX_J = _UxGT("Acel. max") STR_J; - LSTR MSG_AMAX_K = _UxGT("Acel. max") STR_K; - LSTR MSG_AMAX_E = _UxGT("Acel. max") STR_E; + LSTR MSG_AMAX_N = _UxGT("Acel. max@"); + LSTR MSG_AMAX_E = _UxGT("Acel. maxE"); LSTR MSG_AMAX_EN = _UxGT("Acel. max *"); LSTR MSG_A_RETRACT = _UxGT("Acel. retrac."); LSTR MSG_A_TRAVEL = _UxGT("Acel. Viaje"); @@ -302,9 +295,7 @@ namespace Language_es { LSTR MSG_A_STEPS = STR_A _UxGT(" pasos/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" pasos/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" pasos/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" pasos/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" pasos/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" pasos/mm"); + LSTR MSG_N_STEPS = _UxGT("@ pasos/mm"); LSTR MSG_E_STEPS = _UxGT("E pasos/mm"); LSTR MSG_EN_STEPS = _UxGT("* pasos/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -414,6 +405,7 @@ namespace Language_es { LSTR MSG_BABYSTEP_X = _UxGT("Micropaso X"); LSTR MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Micropaso @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Cancelado - Endstop"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Calent. fallido"); @@ -438,8 +430,6 @@ namespace Language_es { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); LSTR MSG_DELTA_SETTINGS = _UxGT("Configuración Delta"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Est. Altura Delta"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Ajustar Sonda Z"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); LSTR MSG_DELTA_HEIGHT = _UxGT("Altura"); LSTR MSG_DELTA_RADIUS = _UxGT("Radio"); @@ -481,13 +471,7 @@ namespace Language_es { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp. Máxima"); LSTR MSG_INFO_PSU = _UxGT("F. Aliment."); LSTR MSG_DRIVE_STRENGTH = _UxGT("Fuerza de empuje"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Driver %"); LSTR MSG_ERROR_TMC = _UxGT("ERROR CONEX. TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIAR FILAMENTO"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 5742fa8f6f97..5504d4da942e 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -56,7 +56,6 @@ namespace Language_eu { LSTR MSG_LEVEL_BED_DONE = _UxGT("Berdintzea eginda"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Etxe. offset eza."); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsetak ezarrita"); - LSTR MSG_SET_ORIGIN = _UxGT("Hasiera ipini"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Berotu ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Berotu ") PREHEAT_1_LABEL " ~"; @@ -139,7 +138,7 @@ namespace Language_eu { LSTR MSG_MOVE_Z = _UxGT("Mugitu Z"); LSTR MSG_MOVE_E = _UxGT("Estrusorea"); LSTR MSG_MOVE_EN = _UxGT("Estrusorea *"); - LSTR MSG_MOVE_N_MM = _UxGT("Mugitu %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Mugitu $mm"); LSTR MSG_MOVE_01MM = _UxGT("Mugitu 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Mugitu 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Mugitu 10mm"); @@ -167,9 +166,7 @@ namespace Language_eu { LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-astindua"); LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-astindua"); LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-astindua"); - LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-astindua"); - LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-astindua"); - LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-astindua"); + LSTR MSG_VN_JERK = _UxGT("V@-astindua"); LSTR MSG_VE_JERK = _UxGT("Ve-astindua"); LSTR MSG_VTRAV_MIN = _UxGT("VBidaia min"); LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); @@ -178,9 +175,7 @@ namespace Language_eu { LSTR MSG_A_STEPS = STR_A _UxGT(" pausoak/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" pausoak/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" pausoak/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" pausoak/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" pausoak/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" pausoak/mm"); + LSTR MSG_N_STEPS = _UxGT("@ pausoak/mm"); LSTR MSG_E_STEPS = _UxGT("E pausoak/mm"); LSTR MSG_EN_STEPS = _UxGT("* pausoak/mm"); LSTR MSG_TEMPERATURE = _UxGT("Tenperatura"); @@ -244,6 +239,7 @@ namespace Language_eu { LSTR MSG_BABYSTEP_X = _UxGT("Mikro-urratsa X"); LSTR MSG_BABYSTEP_Y = _UxGT("Mikro-urratsa Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Mikro-urratsa Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Mikro-urratsa @"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop deusezta."); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Err: Beroketa"); LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: Tenperatura"); @@ -261,7 +257,6 @@ namespace Language_eu { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibratu Zentrua"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta ezarpenak"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibraketa"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Alt. Ezar."); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra diagonala"); LSTR MSG_DELTA_HEIGHT = _UxGT("Altuera"); LSTR MSG_DELTA_RADIUS = _UxGT("Erradioa"); @@ -297,13 +292,7 @@ namespace Language_eu { LSTR MSG_INFO_MAX_TEMP = _UxGT("Tenp. Maximoa"); LSTR MSG_INFO_PSU = _UxGT("Elikadura-iturria"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Driver-aren potentzia"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Driver %"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Idatzi DAC EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("HARIZPIA ALDATU"); LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("HARIZPIA KARGATU"); diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 62f3aae807a5..8fd53a79e36d 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -43,7 +43,6 @@ namespace Language_fi { LSTR MSG_RUN_AUTO_FILES = _UxGT("Automaatti"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Vapauta moottorit"); LSTR MSG_AUTO_HOME = _UxGT("Aja referenssiin"); - LSTR MSG_SET_ORIGIN = _UxGT("Aseta origo"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Esilämmitä ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Esilämmitä ") PREHEAT_1_LABEL " ~"; @@ -72,7 +71,7 @@ namespace Language_fi { LSTR MSG_MOVE_Z = _UxGT("Liikuta Z"); LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); - LSTR MSG_MOVE_N_MM = _UxGT("Liikuta %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Liikuta $mm"); LSTR MSG_MOVE_01MM = _UxGT("Liikuta 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Liikuta 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Liikuta 10mm"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index ae23efd367d7..55b1b4e2e9c9 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -72,11 +72,7 @@ namespace Language_fr { LSTR MSG_HOME_OFFSET_X = _UxGT("Décal. origine X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Décal. origine Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Décal. origine Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Décal. origine ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Décal. origine ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Décal. origine ") STR_K; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Décalages appliqués"); - LSTR MSG_SET_ORIGIN = _UxGT("Régler origine"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Assistant Molettes"); LSTR MSG_SELECT_ORIGIN = _UxGT("Molette du lit"); // Not a selection of the origin LSTR MSG_LAST_VALUE_SP = _UxGT("Ecart origine "); @@ -234,13 +230,11 @@ namespace Language_fr { LSTR MSG_MOVE_X = _UxGT("Déplacer X"); LSTR MSG_MOVE_Y = _UxGT("Déplacer Y"); LSTR MSG_MOVE_Z = _UxGT("Déplacer Z"); - LSTR MSG_MOVE_I = _UxGT("Déplacer ") STR_I; - LSTR MSG_MOVE_J = _UxGT("Déplacer ") STR_J; - LSTR MSG_MOVE_K = _UxGT("Déplacer ") STR_K; + LSTR MSG_MOVE_N = _UxGT("Déplacer @"); LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Buse trop froide"); - LSTR MSG_MOVE_N_MM = _UxGT("Déplacer %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Déplacer $mm"); LSTR MSG_MOVE_01MM = _UxGT("Déplacer 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Déplacer 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Déplacer 10mm"); @@ -283,18 +277,14 @@ namespace Language_fr { LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT(" jerk"); LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT(" jerk"); LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT(" jerk"); - LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT(" jerk"); - LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT(" jerk"); - LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT(" jerk"); + LSTR MSG_VN_JERK = _UxGT("V@ jerk"); LSTR MSG_VE_JERK = _UxGT("Ve jerk"); - LSTR MSG_VELOCITY = _UxGT("Vélocité"); + LSTR MSG_MAX_SPEED = _UxGT("Max Vélocité"); LSTR MSG_VMAX_A = _UxGT("Vit. Max ") STR_A; LSTR MSG_VMAX_B = _UxGT("Vit. Max ") STR_B; LSTR MSG_VMAX_C = _UxGT("Vit. Max ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Vit. Max ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Vit. Max ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Vit. Max ") STR_K; - LSTR MSG_VMAX_E = _UxGT("Vit. Max ") STR_E; + LSTR MSG_VMAX_N = _UxGT("Vit. Max @"); + LSTR MSG_VMAX_E = _UxGT("Vit. Max E"); LSTR MSG_VMAX_EN = _UxGT("Vit. Max *"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Déviat. jonct."); LSTR MSG_VMIN = _UxGT("Vit. Min"); @@ -303,10 +293,8 @@ namespace Language_fr { LSTR MSG_AMAX_A = _UxGT("Max Accél. ") STR_A; LSTR MSG_AMAX_B = _UxGT("Max Accél. ") STR_B; LSTR MSG_AMAX_C = _UxGT("Max Accél. ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Max Accél. ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Max Accél. ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Max Accél. ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Max Accél. ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Max Accél. @"); + LSTR MSG_AMAX_E = _UxGT("Max Accél. E"); LSTR MSG_AMAX_EN = _UxGT("Max Accél. *"); LSTR MSG_A_RETRACT = _UxGT("Acc.rétraction"); LSTR MSG_A_TRAVEL = _UxGT("Acc.course"); @@ -316,9 +304,7 @@ namespace Language_fr { LSTR MSG_A_STEPS = STR_A _UxGT(" pas/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" pas/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" pas/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" pas/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" pas/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" pas/mm"); + LSTR MSG_N_STEPS = _UxGT("@ pas/mm"); LSTR MSG_E_STEPS = _UxGT("E pas/mm"); LSTR MSG_EN_STEPS = _UxGT("* pas/mm"); LSTR MSG_TEMPERATURE = _UxGT("Température"); @@ -444,9 +430,7 @@ namespace Language_fr { LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; + LSTR MSG_BABYSTEP_N = _UxGT("Babystep @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Butée abandon"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Err de chauffe"); @@ -476,8 +460,6 @@ namespace Language_fr { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrer centre"); LSTR MSG_DELTA_SETTINGS = _UxGT("Réglages Delta"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Calibration Auto"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Hauteur Delta"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Delta Z sonde"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diagonale"); LSTR MSG_DELTA_HEIGHT = _UxGT("Hauteur"); LSTR MSG_DELTA_RADIUS = _UxGT("Rayon"); @@ -522,13 +504,7 @@ namespace Language_fr { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp Max"); LSTR MSG_INFO_PSU = _UxGT("Alim."); LSTR MSG_DRIVE_STRENGTH = _UxGT("Puiss. moteur "); - LSTR MSG_DAC_PERCENT_A = _UxGT("Driver ") STR_A _UxGT(" %"); - LSTR MSG_DAC_PERCENT_B = _UxGT("Driver ") STR_B _UxGT(" %"); - LSTR MSG_DAC_PERCENT_C = _UxGT("Driver ") STR_C _UxGT(" %"); - LSTR MSG_DAC_PERCENT_I = _UxGT("Driver ") STR_I _UxGT(" %"); - LSTR MSG_DAC_PERCENT_J = _UxGT("Driver ") STR_J _UxGT(" %"); - LSTR MSG_DAC_PERCENT_K = _UxGT("Driver ") STR_K _UxGT(" %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("Driver E %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("Driver @ %"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM sauv."); LSTR MSG_ERROR_TMC = _UxGT("ERREUR CONNEXION TMC"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 731f89cad4dd..827130de6c46 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -69,7 +69,6 @@ namespace Language_gl { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Compensación Altura"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Axustar Desfases"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfases aplicados"); - LSTR MSG_SET_ORIGIN = _UxGT("Fixar orixe"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Prequentar ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Prequentar ") PREHEAT_1_LABEL " ~"; @@ -227,7 +226,7 @@ namespace Language_gl { LSTR MSG_MOVE_E = _UxGT("Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Bico moi frío"); - LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover $mm"); LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); @@ -262,9 +261,9 @@ namespace Language_gl { LSTR MSG_PID_AUTOTUNE = _UxGT("Auto-Sint. PID"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("Auto-Sint. PID *"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Fin Auto-Sint PID"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-Sint. fallida. Extrusor danado."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-Sint. fallida. Temperatura moi alta."); - LSTR MSG_PID_TIMEOUT = _UxGT("Auto-Sint. fallida. Tempo excedido."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-Sint. fallida! Extrusor danado."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-Sint. fallida! Temperatura moi alta."); + LSTR MSG_PID_TIMEOUT = _UxGT("Auto-Sint. fallida! Tempo excedido."); LSTR MSG_SELECT = _UxGT("Escolla"); LSTR MSG_SELECT_E = _UxGT("Escolla *"); LSTR MSG_ACC = _UxGT("Acel"); @@ -272,30 +271,23 @@ namespace Language_gl { LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); + LSTR MSG_VN_JERK = _UxGT("Max @ Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desvío Unión"); - LSTR MSG_VELOCITY = _UxGT("Velocidade"); - LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Vel"); - LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Vel"); - LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Vel"); - LSTR MSG_VMAX_I = _UxGT("Max ") STR_I _UxGT(" Vel"); - LSTR MSG_VMAX_J = _UxGT("Max ") STR_J _UxGT(" Vel"); - LSTR MSG_VMAX_K = _UxGT("Max ") STR_K _UxGT(" Vel"); - LSTR MSG_VMAX_E = _UxGT("Max ") STR_E _UxGT(" Vel"); - LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); + LSTR MSG_MAX_SPEED = _UxGT("Max Velocidade"); + LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Speed"); + LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Speed"); + LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Speed"); + LSTR MSG_VMAX_N = _UxGT("Max @ Speed"); + LSTR MSG_VMAX_E = _UxGT("Max E Speed"); + LSTR MSG_VMAX_EN = _UxGT("Max * Speed"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("V-viaxe min"); LSTR MSG_ACCELERATION = _UxGT("Aceleración"); LSTR MSG_AMAX_A = _UxGT("Max ") STR_A _UxGT(" Accel"); LSTR MSG_AMAX_B = _UxGT("Max ") STR_B _UxGT(" Accel"); LSTR MSG_AMAX_C = _UxGT("Max ") STR_C _UxGT(" Accel"); - LSTR MSG_AMAX_I = _UxGT("Max ") STR_I _UxGT(" Accel"); - LSTR MSG_AMAX_J = _UxGT("Max ") STR_J _UxGT(" Accel"); - LSTR MSG_AMAX_K = _UxGT("Max ") STR_K _UxGT(" Accel"); - LSTR MSG_AMAX_E = _UxGT("Max ") STR_E _UxGT(" Accel"); + LSTR MSG_AMAX_E = _UxGT("Max E Accel"); LSTR MSG_AMAX_EN = _UxGT("Max * Accel"); LSTR MSG_A_RETRACT = _UxGT("A-retrac."); LSTR MSG_A_TRAVEL = _UxGT("A-viaxe"); @@ -305,9 +297,7 @@ namespace Language_gl { LSTR MSG_A_STEPS = STR_A _UxGT(" pasos/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" pasos/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" pasos/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" pasos/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" pasos/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" pasos/mm"); + LSTR MSG_N_STEPS = _UxGT("@ pasos/mm"); LSTR MSG_E_STEPS = _UxGT("E pasos/mm"); LSTR MSG_EN_STEPS = _UxGT("* pasos/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -430,6 +420,7 @@ namespace Language_gl { LSTR MSG_BABYSTEP_X = _UxGT("Micropaso X"); LSTR MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Micropaso @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Erro FinCarro"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Fallo Quentando"); @@ -454,8 +445,6 @@ namespace Language_gl { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); LSTR MSG_DELTA_SETTINGS = _UxGT("Configuración Delta"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ax. Altura Delta"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Axustar Sonda Z"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); LSTR MSG_DELTA_HEIGHT = _UxGT("Altura"); LSTR MSG_DELTA_RADIUS = _UxGT("Radio"); @@ -497,13 +486,7 @@ namespace Language_gl { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); LSTR MSG_INFO_PSU = _UxGT("Fonte Alimentación"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Forza do Motor"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Driver %"); LSTR MSG_ERROR_TMC = _UxGT("ERRO CONEX. TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIAR FILAMENTO"); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 78db2ad66029..10f11f616f5f 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -53,7 +53,6 @@ namespace Language_hr { LSTR MSG_LEVEL_BED_DONE = _UxGT("Niveliranje gotovo!"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Postavi home offsete"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets postavljeni"); - LSTR MSG_SET_ORIGIN = _UxGT("Postavi ishodište"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Predgrij ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Predgrij ") PREHEAT_1_LABEL " ~"; @@ -79,7 +78,7 @@ namespace Language_hr { LSTR MSG_LEVEL_BED = _UxGT("Niveliraj bed"); LSTR MSG_MOVE_X = _UxGT("Miči X"); LSTR MSG_MOVE_Y = _UxGT("Miči Y"); - LSTR MSG_MOVE_N_MM = _UxGT("Miči %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Miči $mm"); LSTR MSG_MOVE_01MM = _UxGT("Miči 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Miči 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Miči 10mm"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 341d1b467ddb..eebcb759e5e8 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -79,11 +79,7 @@ namespace Language_hu { LSTR MSG_HOME_OFFSET_X = _UxGT("X Kezdö eltol."); LSTR MSG_HOME_OFFSET_Y = _UxGT("Y Kezdö eltol."); LSTR MSG_HOME_OFFSET_Z = _UxGT("Z Kezdö eltol."); - LSTR MSG_HOME_OFFSET_I = _UxGT("Kezdö eltol. ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Kezdö eltol. ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Kezdö eltol. ") STR_K; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); - LSTR MSG_SET_ORIGIN = _UxGT("Eredeti Be"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Elektromos varázsló"); LSTR MSG_SELECT_ORIGIN = _UxGT("Eredeti választása"); LSTR MSG_LAST_VALUE_SP = _UxGT("Utolsó érték "); @@ -260,13 +256,11 @@ namespace Language_hu { LSTR MSG_MOVE_X = _UxGT("X mozgás"); LSTR MSG_MOVE_Y = _UxGT("Y mozgás"); LSTR MSG_MOVE_Z = _UxGT("Z mozgás"); - LSTR MSG_MOVE_I = _UxGT("Mozgás ") STR_I; - LSTR MSG_MOVE_J = _UxGT("Mozgás ") STR_J; - LSTR MSG_MOVE_K = _UxGT("Mozgás ") STR_K; + LSTR MSG_MOVE_N = _UxGT("@ mozgás"); LSTR MSG_MOVE_E = _UxGT("Adagoló"); LSTR MSG_MOVE_EN = _UxGT("Adagoló *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("A fej túl hideg"); - LSTR MSG_MOVE_N_MM = _UxGT("Mozgás %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Mozgás $mm"); LSTR MSG_MOVE_01MM = _UxGT("Mozgás 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Mozgás 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Mozgás 10mm"); @@ -310,8 +304,8 @@ namespace Language_hu { LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID hangolás *"); LSTR MSG_PID_CYCLE = _UxGT("PID ciklus"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID hangolás kész"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz adagoló."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba! Rossz adagoló."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba! Magas hömérséklet."); LSTR MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); LSTR MSG_SELECT = _UxGT("Kiválaszt"); LSTR MSG_SELECT_E = _UxGT("Kiválaszt *"); @@ -320,19 +314,15 @@ namespace Language_hu { LSTR MSG_VA_JERK = _UxGT("Seb.") STR_A _UxGT("-Rántás"); LSTR MSG_VB_JERK = _UxGT("Seb.") STR_B _UxGT("-Rántás"); LSTR MSG_VC_JERK = _UxGT("Seb.") STR_C _UxGT("-Rántás"); - LSTR MSG_VI_JERK = _UxGT("Seb.") STR_I _UxGT("-Rántás"); - LSTR MSG_VJ_JERK = _UxGT("Seb.") STR_J _UxGT("-Rántás"); - LSTR MSG_VK_JERK = _UxGT("Seb.") STR_K _UxGT("-Rántás"); + LSTR MSG_VN_JERK = _UxGT("Seb.@-Rántás"); LSTR MSG_VE_JERK = _UxGT("E ránt. seb."); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Csomopont eltérés"); - LSTR MSG_VELOCITY = _UxGT("Sebesség"); + LSTR MSG_MAX_SPEED = _UxGT("Max Sebesség (mm/s)"); LSTR MSG_VMAX_A = _UxGT("Max Seb. ") STR_A; LSTR MSG_VMAX_B = _UxGT("Max Seb. ") STR_B; LSTR MSG_VMAX_C = _UxGT("Max Seb. ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Max Seb. ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Max Seb. ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Max Seb. ") STR_K; - LSTR MSG_VMAX_E = _UxGT("Max Seb. ") STR_E; + LSTR MSG_VMAX_N = _UxGT("Max Seb. @"); + LSTR MSG_VMAX_E = _UxGT("Max Seb. E"); LSTR MSG_VMAX_EN = _UxGT("Max sebesség *"); LSTR MSG_VMIN = _UxGT("Min sebesség"); LSTR MSG_VTRAV_MIN = _UxGT("Min utazó.seb."); @@ -340,10 +330,8 @@ namespace Language_hu { LSTR MSG_AMAX_A = _UxGT("Max gyors. ") STR_A; LSTR MSG_AMAX_B = _UxGT("Max gyors. ") STR_B; LSTR MSG_AMAX_C = _UxGT("Max gyors. ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Max gyors. ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Max gyors. ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Max gyors. ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Max gyors. ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Max gyors. @"); + LSTR MSG_AMAX_E = _UxGT("Max gyors. E"); LSTR MSG_AMAX_EN = _UxGT("Max gyorsulás *"); LSTR MSG_A_RETRACT = _UxGT("Visszahúzás"); LSTR MSG_A_TRAVEL = _UxGT("Utazás"); @@ -353,9 +341,7 @@ namespace Language_hu { LSTR MSG_A_STEPS = STR_A _UxGT(" Lépés/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" Lépés/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" Lépés/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" Lépés/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" Lépés/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" Lépés/mm"); + LSTR MSG_N_STEPS = _UxGT("@ lépés/mm"); LSTR MSG_E_STEPS = _UxGT("E lépés/mm"); LSTR MSG_EN_STEPS = _UxGT("*Lépés/mm"); LSTR MSG_TEMPERATURE = _UxGT("Höfok"); @@ -489,9 +475,7 @@ namespace Language_hu { LSTR MSG_BABYSTEP_X = _UxGT("Mikrolépés X"); LSTR MSG_BABYSTEP_Y = _UxGT("Mikrolépés Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Mikrolépés Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Mikrolépés ") STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Mikrolépés ") STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Mikrolépés ") STR_K; + LSTR MSG_BABYSTEP_N = _UxGT("Mikrolépés @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Teljes"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Végállás megszakítva!"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Fütés hiba!"); @@ -524,8 +508,6 @@ namespace Language_hu { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Központ kalibrálás"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta beállítások"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto kalibráció"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta magasság kalib."); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z eltolás"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag rúd"); LSTR MSG_DELTA_HEIGHT = _UxGT("Magasság"); LSTR MSG_DELTA_RADIUS = _UxGT("Sugár"); @@ -569,13 +551,7 @@ namespace Language_hu { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max höfok"); LSTR MSG_INFO_PSU = _UxGT("PSU"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Meghajtási erö"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E meghajtó %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ meghajtó %"); LSTR MSG_ERROR_TMC = _UxGT("TMC CSATLAKOZÁSI HIBA"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM írása"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("NYOMTATÓSZÁL CSERE"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 7113fdcd57cd..f0c21deb96cd 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -27,10 +27,9 @@ * 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: + * Substitutions are applied for the following characters when used in menu items titles: * - * $ displays an inserted C-string + * $ displays an inserted string * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) @@ -48,7 +47,10 @@ namespace Language_it { LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pronta."); LSTR MSG_YES = _UxGT("Si"); LSTR MSG_NO = _UxGT("No"); + LSTR MSG_HIGH = _UxGT("ALTO"); + LSTR MSG_LOW = _UxGT("BASSO"); LSTR MSG_BACK = _UxGT("Indietro"); + LSTR MSG_ERROR = _UxGT("Errore"); LSTR MSG_MEDIA_ABORTING = _UxGT("Annullando..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Media inserito"); LSTR MSG_MEDIA_REMOVED = _UxGT("Media rimosso"); @@ -62,6 +64,8 @@ namespace Language_it { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa Soft"); LSTR MSG_MAIN = _UxGT("Menu principale"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Impostaz. avanzate"); + LSTR MSG_TOOLBAR_SETUP = _UxGT("Cnf barra strumenti"); + LSTR MSG_OPTION_DISABLED = _UxGT("Opzione disab."); LSTR MSG_CONFIGURATION = _UxGT("Configurazione"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Esegui files auto"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Disabilita Motori"); @@ -75,6 +79,7 @@ namespace Language_it { LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); LSTR MSG_FILAMENT_SET = _UxGT("Impostaz.filamento"); LSTR MSG_FILAMENT_MAN = _UxGT("Gestione filamento"); + LSTR MSG_MANUAL_LEVELING = _UxGT("Livel.manuale"); LSTR MSG_LEVBED_FL = _UxGT("Davanti Sinistra"); LSTR MSG_LEVBED_FR = _UxGT("Davanti Destra"); LSTR MSG_LEVBED_C = _UxGT("Centro"); @@ -95,14 +100,7 @@ namespace Language_it { LSTR MSG_HOME_OFFSET_X = _UxGT("Offset home X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Offset home Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Offset home Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Offset home ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Offset home ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Offset home ") STR_K; - LSTR MSG_HOME_OFFSET_U = _UxGT("Offset home ") STR_U; - LSTR MSG_HOME_OFFSET_V = _UxGT("Offset home ") STR_V; - LSTR MSG_HOME_OFFSET_W = _UxGT("Offset home ") STR_W; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset applicato"); - LSTR MSG_SET_ORIGIN = _UxGT("Imposta Origine"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Wizard Tramming"); LSTR MSG_SELECT_ORIGIN = _UxGT("Selez. origine"); LSTR MSG_LAST_VALUE_SP = _UxGT("Ultimo valore "); @@ -114,7 +112,14 @@ namespace Language_it { LSTR MSG_PREHEAT_1_ALL = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Tutto"); LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Piatto"); LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" conf"); - + #ifdef PREHEAT_2_LABEL + LSTR MSG_PREHEAT_2 = _UxGT("Preris.") PREHEAT_2_LABEL; + LSTR MSG_PREHEAT_2_SETTINGS = _UxGT("Preris.") PREHEAT_2_LABEL _UxGT(" conf"); + #endif + #ifdef PREHEAT_3_LABEL + LSTR MSG_PREHEAT_3 = _UxGT("Preris.") PREHEAT_3_LABEL; + LSTR MSG_PREHEAT_3_SETTINGS = _UxGT("Preris.") PREHEAT_3_LABEL _UxGT(" conf"); + #endif LSTR MSG_PREHEAT_M = _UxGT("Preriscalda $"); LSTR MSG_PREHEAT_M_H = _UxGT("Preriscalda $ ~"); LSTR MSG_PREHEAT_M_END = _UxGT("Preris.$ Ugello"); @@ -161,10 +166,19 @@ namespace Language_it { LSTR MSG_MESH_VIEW = _UxGT("Visualizza Mesh"); LSTR MSG_EDITING_STOPPED = _UxGT("Modif. Mesh Fermata"); LSTR MSG_NO_VALID_MESH = _UxGT("Mesh non valida"); + LSTR MSG_ACTIVATE_MESH = _UxGT("Attiva livellamento"); LSTR MSG_PROBING_POINT = _UxGT("Punto sondato"); LSTR MSG_MESH_X = _UxGT("Indice X"); LSTR MSG_MESH_Y = _UxGT("Indice Y"); + LSTR MSG_MESH_INSET = _UxGT("Mesh Inset"); + LSTR MSG_MESH_MIN_X = _UxGT("Mesh X minimo"); + LSTR MSG_MESH_MAX_X = _UxGT("Mesh X massimo"); + LSTR MSG_MESH_MIN_Y = _UxGT("Mesh Y minimo"); + LSTR MSG_MESH_MAX_Y = _UxGT("Mesh Y massimo"); + LSTR MSG_MESH_AMAX = _UxGT("Massimizza area"); + LSTR MSG_MESH_CENTER = _UxGT("Area centrale"); LSTR MSG_MESH_EDIT_Z = _UxGT("Valore di Z"); + LSTR MSG_MESH_CANCEL = _UxGT("Mesh cancellato"); LSTR MSG_CUSTOM_COMMANDS = _UxGT("Comandi personaliz."); LSTR MSG_M48_TEST = _UxGT("Test sonda M48"); LSTR MSG_M48_POINT = _UxGT("Punto M48"); @@ -183,6 +197,9 @@ namespace Language_it { LSTR MSG_UBL_TOOLS = _UxGT("Strumenti UBL"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Livel.letto unificato"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Punto inclinaz."); + LSTR MSG_UBL_TILT_MESH = _UxGT("Inclina Mesh"); + LSTR MSG_UBL_TILTING_GRID = _UxGT("Dim.griglia inclin."); + LSTR MSG_UBL_MESH_TILTED = _UxGT("Mesh inclinata"); LSTR MSG_UBL_MANUAL_MESH = _UxGT("Mesh Manuale"); LSTR MSG_UBL_MESH_WIZARD = _UxGT("Creaz.guid.mesh UBL"); LSTR MSG_UBL_BC_INSERT = _UxGT("Metti spes. e misura"); @@ -233,6 +250,7 @@ namespace Language_it { LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Riempimento Manuale"); LSTR MSG_UBL_SMART_FILLIN = _UxGT("Riempimento Smart"); LSTR MSG_UBL_FILLIN_MESH = _UxGT("Riempimento Mesh"); + LSTR MSG_UBL_MESH_FILLED = _UxGT("Pts mancanti riempiti"); LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalida Tutto"); LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalid.Punto Vicino"); LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Ritocca Tutto"); @@ -241,6 +259,7 @@ namespace Language_it { LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Slot di memoria"); LSTR MSG_UBL_LOAD_MESH = _UxGT("Carica Mesh Piatto"); LSTR MSG_UBL_SAVE_MESH = _UxGT("Salva Mesh Piatto"); + LSTR MSG_UBL_INVALID_SLOT = _UxGT("Prima selez. uno slot Mesh"); LSTR MSG_MESH_LOADED = _UxGT("Mesh %i caricata"); LSTR MSG_MESH_SAVED = _UxGT("Mesh %i salvata"); LSTR MSG_UBL_NO_STORAGE = _UxGT("Nessuna memoria"); @@ -285,16 +304,11 @@ namespace Language_it { LSTR MSG_MOVE_X = _UxGT("Muovi X"); LSTR MSG_MOVE_Y = _UxGT("Muovi Y"); LSTR MSG_MOVE_Z = _UxGT("Muovi Z"); - LSTR MSG_MOVE_I = _UxGT("Muovi ") STR_I; - LSTR MSG_MOVE_J = _UxGT("Muovi ") STR_J; - LSTR MSG_MOVE_K = _UxGT("Muovi ") STR_K; - LSTR MSG_MOVE_U = _UxGT("Muovi ") STR_U; - LSTR MSG_MOVE_V = _UxGT("Muovi ") STR_V; - LSTR MSG_MOVE_W = _UxGT("Muovi ") STR_W; + LSTR MSG_MOVE_N = _UxGT("Muovi @"); LSTR MSG_MOVE_E = _UxGT("Estrusore"); LSTR MSG_MOVE_EN = _UxGT("Estrusore *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Ugello freddo"); - LSTR MSG_MOVE_N_MM = _UxGT("Muovi di %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Muovi di $mm"); LSTR MSG_MOVE_01MM = _UxGT("Muovi di 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Muovi di 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Muovi di 10mm"); @@ -304,12 +318,6 @@ namespace Language_it { LSTR MSG_MOVE_01IN = _UxGT("Muovi di 0.1\""); LSTR MSG_MOVE_1IN = _UxGT("Muovi di 1\""); LSTR MSG_SPEED = _UxGT("Velocità"); - LSTR MSG_MAXSPEED = _UxGT("Vel.massima (mm/s)"); - LSTR MSG_MAXSPEED_X = _UxGT("Vel.massima ") STR_A; - LSTR MSG_MAXSPEED_Y = _UxGT("Vel.massima ") STR_B; - LSTR MSG_MAXSPEED_Z = _UxGT("Vel.massima ") STR_C; - LSTR MSG_MAXSPEED_E = _UxGT("Vel.massima ") STR_E; - LSTR MSG_MAXSPEED_A = _UxGT("Vel.massima @"); LSTR MSG_BED_Z = _UxGT("Piatto Z"); LSTR MSG_NOZZLE = _UxGT("Ugello"); LSTR MSG_NOZZLE_N = _UxGT("Ugello ~"); @@ -344,8 +352,12 @@ namespace Language_it { LSTR MSG_PID_AUTOTUNE_E = _UxGT("Calib.PID *"); LSTR MSG_PID_CYCLE = _UxGT("Ciclo PID"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Calibr.PID eseguita"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Calibrazione fallita. Estrusore errato."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita. Temperatura troppo alta."); + LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("Calibr.PID fallito!"); + LSTR MSG_BAD_EXTRUDER_NUM = _UxGT("Estrusore invalido."); + LSTR MSG_TEMP_TOO_HIGH = _UxGT("Temp.troppo alta."); + LSTR MSG_TIMEOUT = _UxGT("Tempo scaduto."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Calibrazione fallita! Estrusore errato."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita! Temperatura troppo alta."); LSTR MSG_PID_TIMEOUT = _UxGT("Calibrazione fallita! Tempo scaduto."); LSTR MSG_MPC_MEASURING_AMBIENT = _UxGT("Testing heat loss"); LSTR MSG_MPC_AUTOTUNE = _UxGT("MPC Autotune"); @@ -362,25 +374,15 @@ namespace Language_it { LSTR MSG_VA_JERK = _UxGT("Max Jerk ") STR_A; LSTR MSG_VB_JERK = _UxGT("Max Jerk ") STR_B; LSTR MSG_VC_JERK = _UxGT("Max Jerk ") STR_C; - LSTR MSG_VI_JERK = _UxGT("Max Jerk ") STR_I; - LSTR MSG_VJ_JERK = _UxGT("Max Jerk ") STR_J; - LSTR MSG_VK_JERK = _UxGT("Max Jerk ") STR_K; - LSTR MSG_VU_JERK = _UxGT("Max Jerk ") STR_U; - LSTR MSG_VV_JERK = _UxGT("Max Jerk ") STR_V; - LSTR MSG_VW_JERK = _UxGT("Max Jerk ") STR_W; + LSTR MSG_VN_JERK = _UxGT("Max Jerk @"); LSTR MSG_VE_JERK = _UxGT("Max Jerk E"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Deviaz. giunzioni"); - LSTR MSG_VELOCITY = _UxGT("Velocità"); + LSTR MSG_MAX_SPEED = _UxGT("Vel.massima (mm/s)"); LSTR MSG_VMAX_A = _UxGT("Vel.Massima ") STR_A; LSTR MSG_VMAX_B = _UxGT("Vel.Massima ") STR_B; LSTR MSG_VMAX_C = _UxGT("Vel.Massima ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Vel.Massima ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Vel.Massima ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Vel.Massima ") STR_K; - LSTR MSG_VMAX_U = _UxGT("Vel.Massima ") STR_U; - LSTR MSG_VMAX_V = _UxGT("Vel.Massima ") STR_V; - LSTR MSG_VMAX_W = _UxGT("Vel.Massima ") STR_W; - LSTR MSG_VMAX_E = _UxGT("Vel.Massima ") STR_E; + LSTR MSG_VMAX_N = _UxGT("Vel.Massima @"); + LSTR MSG_VMAX_E = _UxGT("Vel.Massima E"); LSTR MSG_VMAX_EN = _UxGT("Vel.Massima *"); LSTR MSG_VMIN = _UxGT("Vel.Minima"); LSTR MSG_VTRAV_MIN = _UxGT("Vel.Min spostam."); @@ -388,13 +390,8 @@ namespace Language_it { LSTR MSG_AMAX_A = _UxGT("Acc.Massima ") STR_A; LSTR MSG_AMAX_B = _UxGT("Acc.Massima ") STR_B; LSTR MSG_AMAX_C = _UxGT("Acc.Massima ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Acc.Massima ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Acc.Massima ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Acc.Massima ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Acc.Massima ") STR_E; - LSTR MSG_AMAX_U = _UxGT("Acc.Massima ") STR_U; - LSTR MSG_AMAX_V = _UxGT("Acc.Massima ") STR_V; - LSTR MSG_AMAX_W = _UxGT("Acc.Massima ") STR_W; + LSTR MSG_AMAX_N = _UxGT("Acc.Massima @"); + LSTR MSG_AMAX_E = _UxGT("Acc.Massima E"); LSTR MSG_AMAX_EN = _UxGT("Acc.Massima *"); LSTR MSG_A_RETRACT = _UxGT("A-Ritrazione"); LSTR MSG_A_TRAVEL = _UxGT("A-Spostamento"); @@ -404,12 +401,7 @@ namespace Language_it { LSTR MSG_A_STEPS = STR_A _UxGT(" passi/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" passi/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" passi/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" passi/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" passi/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" passi/mm"); - LSTR MSG_U_STEPS = STR_U _UxGT(" passi/mm"); - LSTR MSG_V_STEPS = STR_V _UxGT(" passi/mm"); - LSTR MSG_W_STEPS = STR_W _UxGT(" passi/mm"); + LSTR MSG_N_STEPS = _UxGT("@ passi/mm"); LSTR MSG_E_STEPS = _UxGT("E passi/mm"); LSTR MSG_EN_STEPS = _UxGT("* passi/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -441,6 +433,10 @@ namespace Language_it { LSTR MSG_RESET_PRINTER = _UxGT("Resetta stampante"); LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aggiorna"); LSTR MSG_INFO_SCREEN = _UxGT("Schermata info"); + LSTR MSG_INFO_MACHINENAME = _UxGT("Nome macchina"); + LSTR MSG_INFO_SIZE = _UxGT("Dimens."); + LSTR MSG_INFO_FWVERSION = _UxGT("Versione firmware"); + LSTR MSG_INFO_BUILD = _UxGT("Dataora compilaz."); LSTR MSG_PREPARE = _UxGT("Prepara"); LSTR MSG_TUNE = _UxGT("Regola"); LSTR MSG_POWER_MONITOR = _UxGT("Controllo aliment."); @@ -466,7 +462,8 @@ namespace Language_it { LSTR MSG_BUTTON_PAUSE = _UxGT("Pausa"); LSTR MSG_BUTTON_RESUME = _UxGT("Riprendi"); LSTR MSG_BUTTON_ADVANCED = _UxGT("Avanzato"); - LSTR MSG_BUTTON_SAVE = _UxGT("Save"); + LSTR MSG_BUTTON_SAVE = _UxGT("Memorizza"); + LSTR MSG_BUTTON_PURGE = _UxGT("Spurga"); LSTR MSG_PAUSING = _UxGT("Messa in pausa..."); LSTR MSG_PAUSE_PRINT = _UxGT("Pausa stampa"); LSTR MSG_ADVANCED_PAUSE = _UxGT("Pausa Avanzata"); @@ -489,9 +486,12 @@ namespace Language_it { LSTR MSG_REMAINING_TIME = _UxGT("Rimanente"); LSTR MSG_PRINT_ABORTED = _UxGT("Stampa Annullata"); LSTR MSG_PRINT_DONE = _UxGT("Stampa Eseguita"); + LSTR MSG_PRINTER_KILLED = _UxGT("Stampante uccisa!"); + LSTR MSG_TURN_OFF = _UxGT("Spegni stampante"); LSTR MSG_NO_MOVE = _UxGT("Nessun Movimento"); LSTR MSG_KILLED = _UxGT("UCCISO. "); LSTR MSG_STOPPED = _UxGT("ARRESTATO. "); + LSTR MSG_FWRETRACT = _UxGT("Ritraz.da firmware"); LSTR MSG_CONTROL_RETRACT = _UxGT("Ritrai mm"); LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Scamb. Ritrai mm"); LSTR MSG_CONTROL_RETRACTF = _UxGT("Ritrai V"); @@ -557,16 +557,14 @@ namespace Language_it { LSTR MSG_ZPROBE_XOFFSET = _UxGT("Offset X sonda"); LSTR MSG_ZPROBE_YOFFSET = _UxGT("Offset Y sonda"); LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z sonda"); + LSTR MSG_ZPROBE_MARGIN = _UxGT("Margine sonda"); + LSTR MSG_Z_FEED_RATE = _UxGT("Velocità Z"); + LSTR MSG_ENABLE_HS_MODE = _UxGT("Abilita modo HS"); LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Muovi ugel.su letto"); LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; - LSTR MSG_BABYSTEP_U = _UxGT("Babystep ") STR_U; - LSTR MSG_BABYSTEP_V = _UxGT("Babystep ") STR_V; - LSTR MSG_BABYSTEP_W = _UxGT("Babystep ") STR_W; + LSTR MSG_BABYSTEP_N = _UxGT("Babystep @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Totali"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Interrompi se FC"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 characters @@ -599,8 +597,6 @@ namespace Language_it { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibra centro"); LSTR MSG_DELTA_SETTINGS = _UxGT("Impostaz. Delta"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto calibrazione"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Imp. altezza Delta"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Offset sonda-Z"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonale"); LSTR MSG_DELTA_HEIGHT = _UxGT("Altezza"); LSTR MSG_DELTA_RADIUS = _UxGT("Raggio"); @@ -627,48 +623,43 @@ namespace Language_it { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosità Luci"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("STAMPANTE ERRATA"); + LSTR MSG_COLORS_GET = _UxGT("Ottieni colori"); + LSTR MSG_COLORS_SELECT = _UxGT("Selez.colori"); + LSTR MSG_COLORS_APPLIED = _UxGT("Colori applicati"); + LSTR MSG_COLORS_RED = _UxGT("Rosso"); + LSTR MSG_COLORS_GREEN = _UxGT("Verde"); + LSTR MSG_COLORS_BLUE = _UxGT("Blu"); + LSTR MSG_COLORS_WHITE = _UxGT("Bianco"); + LSTR MSG_UI_LANGUAGE = _UxGT("Lingua UI"); + LSTR MSG_SOUND_ENABLE = _UxGT("Abilita suono"); + LSTR MSG_LOCKSCREEN = _UxGT("Blocca Schermo"); + LSTR MSG_LOCKSCREEN_LOCKED = _UxGT("Stamp. bloccata,"); + LSTR MSG_LOCKSCREEN_UNLOCK = _UxGT("Scroll x sbloccare."); + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Attendere fino al riavvio."); + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Nessun supporto inserito."); - LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Attendere fino al riavvio."); LSTR MSG_PLEASE_PREHEAT = _UxGT("Si prega di preriscaldare l'hot end."); LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Azzera contatori stampa"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Contatori stampa"); - LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo totale"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Lavoro più lungo"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Totale estruso"); - LSTR MSG_COLORS_GET = _UxGT("Get Color"); - LSTR MSG_COLORS_SELECT = _UxGT("Seleziona colori"); - LSTR MSG_COLORS_APPLIED = _UxGT("Colori applicati"); - LSTR MSG_COLORS_RED = _UxGT("Rosso"); - LSTR MSG_COLORS_GREEN = _UxGT("Verde"); - LSTR MSG_COLORS_BLUE = _UxGT("Blu"); - LSTR MSG_COLORS_WHITE = _UxGT("Bianco"); - LSTR MSG_UI_LANGUAGE = _UxGT("Lingua UI"); - LSTR MSG_SOUND_ENABLE = _UxGT("Abilita suono"); - LSTR MSG_LOCKSCREEN = _UxGT("Blocca Schermo"); #else LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("No Supporto"); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Prerisc. hot end."); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Stampe"); - LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Durata"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Più lungo"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Estruso"); #endif + + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completate"); LSTR MSG_INFO_MIN_TEMP = _UxGT("Temp min"); LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp max"); LSTR MSG_INFO_PSU = _UxGT("Alimentatore"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Potenza Drive"); - LSTR MSG_DAC_PERCENT_A = _UxGT("Driver ") STR_A _UxGT(" %"); - LSTR MSG_DAC_PERCENT_B = _UxGT("Driver ") STR_B _UxGT(" %"); - LSTR MSG_DAC_PERCENT_C = _UxGT("Driver ") STR_C _UxGT(" %"); - LSTR MSG_DAC_PERCENT_I = _UxGT("Driver ") STR_I _UxGT(" %"); - LSTR MSG_DAC_PERCENT_J = _UxGT("Driver ") STR_J _UxGT(" %"); - LSTR MSG_DAC_PERCENT_K = _UxGT("Driver ") STR_K _UxGT(" %"); - LSTR MSG_DAC_PERCENT_U = _UxGT("Driver ") STR_U _UxGT(" %"); - LSTR MSG_DAC_PERCENT_V = _UxGT("Driver ") STR_V _UxGT(" %"); - LSTR MSG_DAC_PERCENT_W = _UxGT("Driver ") STR_W _UxGT(" %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("Driver E %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("Driver @ %"); LSTR MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIO FILAMENTO"); @@ -678,10 +669,14 @@ namespace Language_it { LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPZIONI RIPRESA:"); LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Spurga di più"); LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Riprendi stampa"); + LSTR MSG_FILAMENT_CHANGE_PURGE_CONTINUE = _UxGT("Spurga o continua?"); LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Ugello: "); LSTR MSG_RUNOUT_SENSOR = _UxGT("Sens.filo termin."); // Max 17 characters LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm filo term."); LSTR MSG_RUNOUT_ENABLE = _UxGT("Abil.filo termin."); + LSTR MSG_RUNOUT_ACTIVE = _UxGT("Filo termin. attivo"); + LSTR MSG_INVERT_EXTRUDER = _UxGT("Inverti estrusore"); + LSTR MSG_EXTRUDER_MIN_TEMP = _UxGT("Temp.min estrusore"); LSTR MSG_FANCHECK = _UxGT("Verif.tacho vent."); // Max 17 characters LSTR MSG_KILL_HOMING_FAILED = _UxGT("Home fallito"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondaggio fallito"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 164dca8fcfe2..0a53ee50d21f 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -61,7 +61,6 @@ namespace Language_jp_kana { LSTR MSG_LEVEL_BED_DONE = _UxGT("レベリングカンリョウ"); // "Leveling Done!" LSTR MSG_SET_HOME_OFFSETS = _UxGT("キジュンオフセットセッテイ"); // "Set home offsets" LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("オフセットガテキヨウサレマシタ"); // "Offsets applied" - LSTR MSG_SET_ORIGIN = _UxGT("キジュンセット"); // "Set origin" #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" ヨネツ"); // "Preheat " PREHEAT_1_LABEL LSTR MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" ヨネツ ~"); // "Preheat " PREHEAT_1_LABEL @@ -94,7 +93,7 @@ namespace Language_jp_kana { LSTR MSG_MOVE_Y = _UxGT("Yジク イドウ"); // "Move Y" LSTR MSG_MOVE_Z = _UxGT("Zジク イドウ"); // "Move Z" LSTR MSG_MOVE_E = _UxGT("エクストルーダー"); // "Extruder" - LSTR MSG_MOVE_N_MM = _UxGT("%smm イドウ"); // "Move 0.025mm" + LSTR MSG_MOVE_N_MM = _UxGT("$mm イドウ"); // "Move 0.025mm" LSTR MSG_MOVE_01MM = _UxGT("0.1mm イドウ"); // "Move 0.1mm" LSTR MSG_MOVE_1MM = _UxGT(" 1mm イドウ"); // "Move 1mm" LSTR MSG_MOVE_10MM = _UxGT(" 10mm イドウ"); // "Move 10mm" @@ -119,20 +118,16 @@ namespace Language_jp_kana { LSTR MSG_VA_JERK = _UxGT("ジク ヤクドウ mm/s") STR_A; // "Va-jerk" LSTR MSG_VB_JERK = _UxGT("ジク ヤクドウ mm/s") STR_B; // "Vb-jerk" LSTR MSG_VC_JERK = _UxGT("ジク ヤクドウ mm/s") STR_C; // "Vc-jerk" - LSTR MSG_VI_JERK = _UxGT("ジク ヤクドウ mm/s") STR_I; // "Va-jerk" - LSTR MSG_VJ_JERK = _UxGT("ジク ヤクドウ mm/s") STR_J; // "Vb-jerk" - LSTR MSG_VK_JERK = _UxGT("ジク ヤクドウ mm/s") STR_K; // "Vc-jerk" + LSTR MSG_VN_JERK = _UxGT("ジク ヤクドウ mm/s@"); // "V@-jerk" LSTR MSG_A_STEPS = STR_A _UxGT("ステップ/mm"); LSTR MSG_B_STEPS = STR_B _UxGT("ステップ/mm"); LSTR MSG_C_STEPS = STR_C _UxGT("ステップ/mm"); + LSTR MSG_N_STEPS = _UxGT("@ステップ/mm"); LSTR MSG_VE_JERK = _UxGT("エクストルーダー ヤクド"); // "Ve-jerk" LSTR MSG_VMAX_A = _UxGT("サイダイオクリソクド ") STR_A; // "Vmax A" LSTR MSG_VMAX_B = _UxGT("サイダイオクリソクド ") STR_B; // "Vmax B" LSTR MSG_VMAX_C = _UxGT("サイダイオクリソクド ") STR_C; // "Vmax C" - LSTR MSG_VMAX_I = _UxGT("サイダイオクリソクド ") STR_I; // "Vmax I" - LSTR MSG_VMAX_J = _UxGT("サイダイオクリソクド ") STR_J; // "Vmax J" - LSTR MSG_VMAX_K = _UxGT("サイダイオクリソクド ") STR_K; // "Vmax K" - LSTR MSG_VMAX_E = _UxGT("サイダイオクリソクド ") STR_E; // "Vmax E" + LSTR MSG_VMAX_E = _UxGT("サイダイオクリソクド E"); // "Vmax E" LSTR MSG_VMAX_EN = _UxGT("サイダイオクリソクド *"); // "Vmax E1" LSTR MSG_VMIN = _UxGT("サイショウオクリソクド"); // "Vmin" LSTR MSG_VTRAV_MIN = _UxGT("サイショウイドウソクド"); // "VTrav min" @@ -216,13 +211,7 @@ namespace Language_jp_kana { LSTR MSG_INFO_MAX_TEMP = _UxGT("セッテイサイコウオン"); // "Max Temp" LSTR MSG_INFO_PSU = _UxGT("デンゲンシュベツ"); // "Power Supply" LSTR MSG_DRIVE_STRENGTH = _UxGT("モータークドウリョク"); // "Drive Strength" - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" DACシュツリョク %"); // "X Driver %" - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" DACシュツリョク %"); // "Y Driver %" - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" DACシュツリョク %"); // "Z Driver %" - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" DACシュツリョク %"); // "I Driver %" - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" DACシュツリョク %"); // "J Driver %" - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" DACシュツリョク %"); // "K Driver %" - LSTR MSG_DAC_PERCENT_E = _UxGT("E DACシュツリョク %"); // "E Driver %" + LSTR MSG_DAC_PERCENT_N = _UxGT("@ DACシュツリョク %"); // "@ Driver %" LSTR MSG_DAC_EEPROM_WRITE = _UxGT("EEPROMヘホゾン"); // "Store memory" LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("イチジテイシ"); LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("プリントサイカイ"); // "Resume print" @@ -250,7 +239,7 @@ namespace Language_jp_kana { LSTR MSG_YES = _UxGT("ハイ"); LSTR MSG_NO = _UxGT("イイエ"); LSTR MSG_BACK = _UxGT("モドリ"); - LSTR MSG_VELOCITY = _UxGT("ソクド"); + LSTR MSG_MAX_SPEED = _UxGT("ソクド"); LSTR MSG_STEPS_PER_MM = _UxGT("ステップ/mm"); LSTR MSG_CUSTOM_COMMANDS = _UxGT("ユーザーコマンド"); LSTR MSG_PRINT_PAUSED = _UxGT("プリントガイチジテイシサレマシタ"); diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index e55ed9fea78f..ca51198034ea 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -53,7 +53,6 @@ namespace Language_nl { LSTR MSG_LEVEL_BED_DONE = _UxGT("Bed level kompl."); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Zet home offsets"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("H offset toegep."); - LSTR MSG_SET_ORIGIN = _UxGT("Nulpunt instellen"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" voorverwarmen"); LSTR MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" voorverw. ~"); @@ -87,7 +86,7 @@ namespace Language_nl { LSTR MSG_MOVE_Z = _UxGT("Verplaats Z"); LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); - LSTR MSG_MOVE_N_MM = _UxGT("Verplaats %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Verplaats $mm"); LSTR MSG_MOVE_01MM = _UxGT("Verplaats 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Verplaats 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Verplaats 10mm"); @@ -158,6 +157,7 @@ namespace Language_nl { LSTR MSG_BABYSTEP_X = _UxGT("Babystap X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystap Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystap Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Babystap @"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop afbr."); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Voorverw. fout"); LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Redun. temp fout"); @@ -173,8 +173,8 @@ namespace Language_nl { LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibreer Y"); LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibreer Z"); LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibreer Midden"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta conf"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibratie"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Zet Delta Hoogte"); LSTR MSG_CASE_LIGHT = _UxGT("Case licht"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 47c89e9e3291..34155f87fed8 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -27,10 +27,9 @@ * 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: + * Substitutions are applied for the following characters when used in menu items titles: * - * $ displays an inserted C-string + * $ displays an inserted string * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) @@ -80,7 +79,6 @@ namespace Language_pl { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Wys. zanikania"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ust. poz. zer."); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Poz. zerowa ust."); - LSTR MSG_SET_ORIGIN = _UxGT("Ustaw punkt zero"); LSTR MSG_SELECT_ORIGIN = _UxGT("Wybierz punkt zero"); LSTR MSG_LAST_VALUE_SP = _UxGT("Poprzednia wartość "); #if HAS_PREHEAT @@ -240,7 +238,7 @@ namespace Language_pl { LSTR MSG_MOVE_E = _UxGT("Ekstruzja (os E)"); LSTR MSG_MOVE_EN = _UxGT("Ekstruzja (os E) *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Dysza za zimna"); - LSTR MSG_MOVE_N_MM = _UxGT("Przesuń co %s mm"); + LSTR MSG_MOVE_N_MM = _UxGT("Przesuń co $ mm"); LSTR MSG_MOVE_01MM = _UxGT("Przesuń co .1 mm"); LSTR MSG_MOVE_1MM = _UxGT("Przesuń co 1 mm"); LSTR MSG_MOVE_10MM = _UxGT("Przesuń co 10 mm"); @@ -277,11 +275,9 @@ namespace Language_pl { LSTR MSG_VA_JERK = _UxGT("Zryw V") STR_A; LSTR MSG_VB_JERK = _UxGT("Zryw V") STR_B; LSTR MSG_VC_JERK = _UxGT("Zryw V") STR_C; - LSTR MSG_VI_JERK = _UxGT("Zryw V") STR_I; - LSTR MSG_VJ_JERK = _UxGT("Zryw V") STR_J; - LSTR MSG_VK_JERK = _UxGT("Zryw V") STR_K; + LSTR MSG_VN_JERK = _UxGT("Zryw V@"); LSTR MSG_VE_JERK = _UxGT("Zryw Ve"); - LSTR MSG_VELOCITY = _UxGT("Prędkość (V)"); + LSTR MSG_MAX_SPEED = _UxGT("Prędkość (V)"); LSTR MSG_VTRAV_MIN = _UxGT("Vskok min"); LSTR MSG_ACCELERATION = _UxGT("Przyspieszenie (A)"); @@ -293,9 +289,7 @@ namespace Language_pl { LSTR MSG_A_STEPS = STR_A _UxGT(" kroki/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" kroki/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" kroki/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" kroki/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" kroki/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" kroki/mm"); + LSTR MSG_N_STEPS = _UxGT("@ kroki/mm"); LSTR MSG_E_STEPS = _UxGT("E kroki/mm"); LSTR MSG_EN_STEPS = _UxGT("* kroki/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -406,8 +400,6 @@ namespace Language_pl { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibruj środek"); LSTR MSG_DELTA_SETTINGS = _UxGT("Ustawienia delty"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto kalibrowanie"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ustaw wysokość delty"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Przesun. Z sondy"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Ukośne ramię"); LSTR MSG_DELTA_HEIGHT = _UxGT("Wysokość"); LSTR MSG_DELTA_RADIUS = _UxGT("Promień"); @@ -446,13 +438,7 @@ namespace Language_pl { LSTR MSG_INFO_PSU = _UxGT("Zasilacz"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Siła %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Siła %"); LSTR MSG_ERROR_TMC = _UxGT("TMC BŁĄD POŁĄCZENIA"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Zapisz DAC EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("ZMIEŃ FILAMENT"); diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index f73fe1f1b481..69df8bdf5427 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -52,7 +52,6 @@ namespace Language_pt { LSTR MSG_LEVEL_BED_DONE = _UxGT("Pronto !"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Definir desvio"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets aplicados"); - LSTR MSG_SET_ORIGIN = _UxGT("Definir origem"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL " ~"; @@ -81,7 +80,7 @@ namespace Language_pt { LSTR MSG_MOVE_Z = _UxGT("Mover Z"); LSTR MSG_MOVE_E = _UxGT("Mover Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Mover Extrusor *"); - LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover $mm"); LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); @@ -105,9 +104,7 @@ namespace Language_pt { LSTR MSG_A_STEPS = STR_A _UxGT(" passo/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" passo/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" passo/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" passo/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" passo/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" passo/mm"); + LSTR MSG_N_STEPS = _UxGT("@ passo/mm"); LSTR MSG_E_STEPS = _UxGT("E passo/mm"); LSTR MSG_EN_STEPS = _UxGT("* passo/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 8d8c65f63d4e..0f0f8c5287c2 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -67,7 +67,6 @@ namespace Language_pt_br { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Suavizar altura"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Compensar origem"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Alteração aplicada"); - LSTR MSG_SET_ORIGIN = _UxGT("Ajustar Origem"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL " ~"; @@ -213,7 +212,7 @@ namespace Language_pt_br { LSTR MSG_MOVE_E = _UxGT("Mover Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Mover Extrusor *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Extrus. mto fria"); - LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover $mm"); LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); @@ -243,12 +242,10 @@ namespace Language_pt_br { LSTR MSG_VA_JERK = _UxGT("arrancada V") STR_A; LSTR MSG_VB_JERK = _UxGT("arrancada V") STR_B; LSTR MSG_VC_JERK = _UxGT("arrancada V") STR_C; - LSTR MSG_VI_JERK = _UxGT("arrancada V") STR_I; - LSTR MSG_VJ_JERK = _UxGT("arrancada V") STR_J; - LSTR MSG_VK_JERK = _UxGT("arrancada V") STR_K; + LSTR MSG_VN_JERK = _UxGT("arrancada V@"); LSTR MSG_VE_JERK = _UxGT("arrancada VE"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desv. Junção"); - LSTR MSG_VELOCITY = _UxGT("Velocidade"); + LSTR MSG_MAX_SPEED = _UxGT("Velocidade"); LSTR MSG_VTRAV_MIN = _UxGT("VDeslocamento min"); LSTR MSG_ACCELERATION = _UxGT("Aceleração"); LSTR MSG_A_RETRACT = _UxGT("Retrair A"); @@ -257,9 +254,7 @@ namespace Language_pt_br { LSTR MSG_A_STEPS = _UxGT("Passo ") STR_A _UxGT("/mm"); LSTR MSG_B_STEPS = _UxGT("Passo ") STR_B _UxGT("/mm"); LSTR MSG_C_STEPS = _UxGT("Passo ") STR_C _UxGT("/mm"); - LSTR MSG_I_STEPS = _UxGT("Passo ") STR_I _UxGT("/mm"); - LSTR MSG_J_STEPS = _UxGT("Passo ") STR_J _UxGT("/mm"); - LSTR MSG_K_STEPS = _UxGT("Passo ") STR_K _UxGT("/mm"); + LSTR MSG_N_STEPS = _UxGT("Passo @/mm"); LSTR MSG_E_STEPS = _UxGT("E/mm"); LSTR MSG_EN_STEPS = _UxGT("*/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -353,6 +348,7 @@ namespace Language_pt_br { LSTR MSG_BABYSTEP_X = _UxGT("Passinho X"); LSTR MSG_BABYSTEP_Y = _UxGT("Passinho Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Passinho Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Passinho @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Abortar Fim de Curso"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Aquecimento falhou"); @@ -377,8 +373,6 @@ namespace Language_pt_br { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); LSTR MSG_DELTA_SETTINGS = _UxGT("Configuração Delta"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto-Calibração"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Calibrar Altura"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Desloc. Sonda Z"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Haste Diagonal"); LSTR MSG_DELTA_HEIGHT = _UxGT("Altura"); LSTR MSG_DELTA_RADIUS = _UxGT("Raio"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index f51179829a8e..3bd15f18a492 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -68,7 +68,6 @@ namespace Language_ro { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Fade Inaltime"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Seteaza Offseturile Acasa"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offseturi Aplicate"); - LSTR MSG_SET_ORIGIN = _UxGT("Seteaza Originea"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Preincalzeste ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Preincalzeste ") PREHEAT_1_LABEL " ~"; @@ -226,7 +225,7 @@ namespace Language_ro { LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Capat Prea Rece"); - LSTR MSG_MOVE_N_MM = _UxGT("Move %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Move $mm"); LSTR MSG_MOVE_01MM = _UxGT("Move 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Move 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Move 10mm"); @@ -261,8 +260,8 @@ namespace Language_ro { LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed! Bad extruder."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed! Temperature too high."); LSTR MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); LSTR MSG_SELECT = _UxGT("Select"); LSTR MSG_SELECT_E = _UxGT("Select *"); @@ -271,30 +270,24 @@ namespace Language_ro { LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-Jerk"); LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-Jerk"); LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-Jerk"); - LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-Jerk"); - LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-Jerk"); - LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-Jerk"); + LSTR MSG_VN_JERK = _UxGT("V@-Jerk"); LSTR MSG_VE_JERK = _UxGT("Ve-Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); - LSTR MSG_VELOCITY = _UxGT("Velocity"); - LSTR MSG_VMAX_A = _UxGT("Vmax ") STR_A; - LSTR MSG_VMAX_B = _UxGT("Vmax ") STR_B; - LSTR MSG_VMAX_C = _UxGT("Vmax ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Vmax ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Vmax ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Vmax ") STR_K; - LSTR MSG_VMAX_E = _UxGT("Vmax ") STR_E; - LSTR MSG_VMAX_EN = _UxGT("Vmax *"); + LSTR MSG_MAX_SPEED = _UxGT("Max Speed"); + LSTR MSG_VMAX_A = _UxGT("Max Speed ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Max Speed ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Max Speed ") STR_C; + LSTR MSG_VMAX_N = _UxGT("Max Speed @"); + LSTR MSG_VMAX_E = _UxGT("Max Speed E"); + LSTR MSG_VMAX_EN = _UxGT("Max Speed *"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); LSTR MSG_ACCELERATION = _UxGT("Acceleration"); LSTR MSG_AMAX_A = _UxGT("Amax ") STR_A; LSTR MSG_AMAX_B = _UxGT("Amax ") STR_B; LSTR MSG_AMAX_C = _UxGT("Amax ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Amax ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Amax ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Amax ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Amax ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Amax @"); + LSTR MSG_AMAX_E = _UxGT("Amax E"); LSTR MSG_AMAX_EN = _UxGT("Amax *"); LSTR MSG_A_RETRACT = _UxGT("A-Retract"); LSTR MSG_A_TRAVEL = _UxGT("A-Travel"); @@ -304,11 +297,9 @@ namespace Language_ro { LSTR MSG_A_STEPS = STR_A _UxGT(" steps/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" steps/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" steps/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" steps/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" steps/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" steps/mm"); - LSTR MSG_E_STEPS = _UxGT("Esteps/mm"); - LSTR MSG_EN_STEPS = _UxGT("*steps/mm"); + LSTR MSG_N_STEPS = _UxGT("@ steps/mm"); + LSTR MSG_E_STEPS = _UxGT("E steps/mm"); + LSTR MSG_EN_STEPS = _UxGT("* steps/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperature"); LSTR MSG_MOTION = _UxGT("Motion"); LSTR MSG_FILAMENT = _UxGT("Filament"); @@ -436,6 +427,7 @@ namespace Language_ro { LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Babystep @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); @@ -460,8 +452,6 @@ namespace Language_ro { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrate Center"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Settings"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibration"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Set Delta Height"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Probe Z-offset"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); LSTR MSG_DELTA_HEIGHT = _UxGT("Inaltime"); LSTR MSG_DELTA_RADIUS = _UxGT("Radius"); @@ -504,13 +494,7 @@ namespace Language_ro { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temperatura Maxima"); LSTR MSG_INFO_PSU = _UxGT("PSU"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Driver %"); LSTR MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMENT CHANGE"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index d6b5bbfbdf04..c9b4683bb20d 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -84,20 +84,13 @@ namespace Language_ru { LSTR MSG_HOME_OFFSET_X = _UxGT("Смещение дома X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Смещение дома Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Смещение дома Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Смещение дома ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Смещение дома ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Смещение дома ") STR_K; #else LSTR MSG_SET_HOME_OFFSETS = _UxGT("Установ.смещ.дома"); LSTR MSG_HOME_OFFSET_X = _UxGT("Смещ. дома X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Смещ. дома Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Смещ. дома Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Смещ. дома ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Смещ. дома ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Смещ. дома ") STR_K; #endif LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Смещения применены"); - LSTR MSG_SET_ORIGIN = _UxGT("Установить ноль"); LSTR MSG_SELECT_ORIGIN = _UxGT("Выберите ноль"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_LAST_VALUE_SP = _UxGT("Последнее знач. "); @@ -339,9 +332,7 @@ namespace Language_ru { LSTR MSG_MOVE_X = _UxGT("Движение по X"); LSTR MSG_MOVE_Y = _UxGT("Движение по Y"); LSTR MSG_MOVE_Z = _UxGT("Движение по Z"); - LSTR MSG_MOVE_I = _UxGT("Движение по ") STR_I; - LSTR MSG_MOVE_J = _UxGT("Движение по ") STR_J; - LSTR MSG_MOVE_K = _UxGT("Движение по ") STR_K; + LSTR MSG_MOVE_N = _UxGT("Движение по @"); LSTR MSG_MOVE_E = _UxGT("Экструдер"); LSTR MSG_MOVE_EN = _UxGT("Экструдер *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Сопло не нагрето"); @@ -391,8 +382,8 @@ namespace Language_ru { LSTR MSG_PID_AUTOTUNE = _UxGT("Автоподбор PID"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("Автоподбор PID *"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Подбор PID выполнен"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Сбой автоподбора. Плохой экструдер."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Сбой автоподбора. Температура повышена."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Сбой автоподбора! Плохой экструдер."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Сбой автоподбора! Температура повышена."); LSTR MSG_PID_TIMEOUT = _UxGT("Сбой автоподбора! Завершение времени."); LSTR MSG_SELECT = _UxGT("Выбор"); @@ -402,23 +393,19 @@ namespace Language_ru { LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-рывок"); LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-рывок"); LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-рывок"); - LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-рывок"); - LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-рывок"); - LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-рывок"); + LSTR MSG_VN_JERK = _UxGT("V@-рывок"); LSTR MSG_VE_JERK = _UxGT("Ve-рывок"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_JUNCTION_DEVIATION = _UxGT("Отклонение узла"); #else LSTR MSG_JUNCTION_DEVIATION = _UxGT("Отклон. узла"); #endif - LSTR MSG_VELOCITY = _UxGT("Скорость, мм/с"); + LSTR MSG_MAX_SPEED = _UxGT("Скорость, мм/с"); LSTR MSG_VMAX_A = _UxGT("Скор.макс ") STR_A; LSTR MSG_VMAX_B = _UxGT("Скор.макс ") STR_B; LSTR MSG_VMAX_C = _UxGT("Скор.макс ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Скор.макс ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Скор.макс ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Скор.макс ") STR_K; - LSTR MSG_VMAX_E = _UxGT("Скор.макс ") STR_E; + LSTR MSG_VMAX_N = _UxGT("Скор.макс @"); + LSTR MSG_VMAX_E = _UxGT("Скор.макс E"); LSTR MSG_VMAX_EN = _UxGT("Скор.макс *"); LSTR MSG_VMIN = _UxGT("Скор.мин"); LSTR MSG_VTRAV_MIN = _UxGT("Перемещение мин"); @@ -426,10 +413,8 @@ namespace Language_ru { LSTR MSG_AMAX_A = _UxGT("Ускор.макс ") STR_A; LSTR MSG_AMAX_B = _UxGT("Ускор.макс ") STR_B; LSTR MSG_AMAX_C = _UxGT("Ускор.макс ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Ускор.макс ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Ускор.макс ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Ускор.макс ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Ускор.макс ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Ускор.макс @"); + LSTR MSG_AMAX_E = _UxGT("Ускор.макс E"); LSTR MSG_AMAX_EN = _UxGT("Ускор.макс *"); LSTR MSG_A_RETRACT = _UxGT("Ускор.втягив."); LSTR MSG_A_TRAVEL = _UxGT("Ускор.путеш."); @@ -439,9 +424,7 @@ namespace Language_ru { LSTR MSG_A_STEPS = STR_A _UxGT(" шаг/мм"); LSTR MSG_B_STEPS = STR_B _UxGT(" шаг/мм"); LSTR MSG_C_STEPS = STR_C _UxGT(" шаг/мм"); - LSTR MSG_I_STEPS = STR_I _UxGT(" шаг/мм"); - LSTR MSG_J_STEPS = STR_J _UxGT(" шаг/мм"); - LSTR MSG_K_STEPS = STR_K _UxGT(" шаг/мм"); + LSTR MSG_N_STEPS = _UxGT("@ шаг/мм"); LSTR MSG_E_STEPS = _UxGT("E шаг/мм"); LSTR MSG_EN_STEPS = _UxGT("* шаг/мм"); LSTR MSG_TEMPERATURE = _UxGT("Температура"); @@ -612,9 +595,7 @@ namespace Language_ru { LSTR MSG_BABYSTEP_X = _UxGT("Микрошаг X"); LSTR MSG_BABYSTEP_Y = _UxGT("Микрошаг Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Микрошаг Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Микрошаг ") STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Микрошаг ") STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Микрошаг ") STR_K; + LSTR MSG_BABYSTEP_N = _UxGT("Микрошаг @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Сработал концевик"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Разогрев не удался"); @@ -647,12 +628,6 @@ namespace Language_ru { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калибровать центр"); LSTR MSG_DELTA_SETTINGS = _UxGT("Настройки Delta"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Авто калибровка"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Высота Delta"); - #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещения"); - #else - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондир. Z-смещения"); - #endif LSTR MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); LSTR MSG_DELTA_HEIGHT = _UxGT("Высота"); LSTR MSG_DELTA_RADIUS = _UxGT("Радиус"); @@ -711,13 +686,7 @@ namespace Language_ru { LSTR MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; LSTR MSG_INFO_PSU = _UxGT("БП"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Сила привода"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Привод, %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Привод, %"); LSTR MSG_ERROR_TMC = _UxGT("СБОЙ СВЯЗИ С TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Запись DAC в EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("ЗАМЕНА ФИЛАМЕНТА"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 64e298cb152e..ef1396e81ff3 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -31,10 +31,9 @@ * 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: + * Substitutions are applied for the following characters when used in menu items titles: * - * $ displays an inserted C-string + * $ displays an inserted string * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) @@ -51,7 +50,10 @@ namespace Language_sk { LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pripravená."); LSTR MSG_YES = _UxGT("ÁNO"); LSTR MSG_NO = _UxGT("NIE"); + LSTR MSG_HIGH = _UxGT("VYSOKÁ"); + LSTR MSG_LOW = _UxGT("NÍZKA"); LSTR MSG_BACK = _UxGT("Naspäť"); + LSTR MSG_ERROR = _UxGT("Chyba"); LSTR MSG_MEDIA_ABORTING = _UxGT("Ruším..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Karta vložená"); LSTR MSG_MEDIA_REMOVED = _UxGT("Karta vybraná"); @@ -65,6 +67,8 @@ namespace Language_sk { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft. endstopy"); LSTR MSG_MAIN = _UxGT("Hlavná ponuka"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Pokročilé nastav."); + LSTR MSG_TOOLBAR_SETUP = _UxGT("Panel nástrojov"); + LSTR MSG_OPTION_DISABLED = _UxGT("Možnosť vypnutá"); LSTR MSG_CONFIGURATION = _UxGT("Konfigurácia"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Auto-štart"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Uvolniť motory"); @@ -78,6 +82,7 @@ namespace Language_sk { LSTR MSG_AUTO_HOME_Z = _UxGT("Domov os Z"); LSTR MSG_FILAMENT_SET = _UxGT("Nastav. filamentu"); LSTR MSG_FILAMENT_MAN = _UxGT("Správa filamentu"); + LSTR MSG_MANUAL_LEVELING = _UxGT("Ručné rovnanie"); LSTR MSG_LEVBED_FL = _UxGT("Ľavý predný"); LSTR MSG_LEVBED_FR = _UxGT("Pravý predný"); LSTR MSG_LEVBED_C = _UxGT("Stred"); @@ -98,11 +103,7 @@ namespace Language_sk { LSTR MSG_HOME_OFFSET_X = _UxGT("X Ofset"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Y Ofset"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); - LSTR MSG_HOME_OFFSET_I = STR_I _UxGT(" Ofset"); - LSTR MSG_HOME_OFFSET_J = STR_J _UxGT(" Ofset"); - LSTR MSG_HOME_OFFSET_K = STR_K _UxGT(" Ofset"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); - LSTR MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Spriev. vyrovn."); LSTR MSG_SELECT_ORIGIN = _UxGT("Vyberte začiatok"); LSTR MSG_LAST_VALUE_SP = _UxGT("Posl. hodnota "); @@ -114,7 +115,14 @@ namespace Language_sk { LSTR MSG_PREHEAT_1_ALL = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" všetko"); LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" podlož"); LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" nast."); - + #ifdef PREHEAT_2_LABEL + LSTR MSG_PREHEAT_2 = _UxGT("Zahriať ") PREHEAT_2_LABEL; + LSTR MSG_PREHEAT_2_SETTINGS = _UxGT("Zahriať ") PREHEAT_2_LABEL _UxGT(" nast."); + #endif + #ifdef PREHEAT_3_LABEL + LSTR MSG_PREHEAT_3 = _UxGT("Zahriať ") PREHEAT_3_LABEL; + LSTR MSG_PREHEAT_3_SETTINGS = _UxGT("Zahriať ") PREHEAT_3_LABEL _UxGT(" nast."); + #endif LSTR MSG_PREHEAT_M = _UxGT("Zahriať $"); LSTR MSG_PREHEAT_M_H = _UxGT("Zahriať $ ~"); LSTR MSG_PREHEAT_M_END = _UxGT("Zahriať $ hotend"); @@ -149,7 +157,8 @@ namespace Language_sk { LSTR MSG_BED_LEVELING = _UxGT("Vyrovnanie podložky"); LSTR MSG_LEVEL_BED = _UxGT("Vyrovnať podložku"); LSTR MSG_BED_TRAMMING = _UxGT("Vyrovnať rohy"); - LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Zdvyhnite podl., kým sa nezopne sonda"); + LSTR MSG_BED_TRAMMING_MANUAL = _UxGT("Ručné vyrovnanie"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Zdvihnite podl., kým sa nezopne sonda"); LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Rohy sú vrámci odchyl. Vyrovnajte podl."); LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Dobré body: "); LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Posl. Z: "); @@ -160,10 +169,19 @@ namespace Language_sk { LSTR MSG_MESH_VIEW = _UxGT("Zobraz. sieť bodov"); LSTR MSG_EDITING_STOPPED = _UxGT("Koniec úprav siete"); LSTR MSG_NO_VALID_MESH = _UxGT("Neplatná sieť bodov"); + LSTR MSG_ACTIVATE_MESH = _UxGT("Zapnúť vyrovnanie"); LSTR MSG_PROBING_POINT = _UxGT("Skúšam bod"); LSTR MSG_MESH_X = _UxGT("Index X"); LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_INSET = _UxGT("Vložiť sieť"); + LSTR MSG_MESH_MIN_X = _UxGT("Min. X sieťe"); + LSTR MSG_MESH_MAX_X = _UxGT("Max. X sieťe"); + LSTR MSG_MESH_MIN_Y = _UxGT("Min. Y sieťe"); + LSTR MSG_MESH_MAX_Y = _UxGT("Max. Y sieťe"); + LSTR MSG_MESH_AMAX = _UxGT("Maximál. oblasť"); + LSTR MSG_MESH_CENTER = _UxGT("Stredová oblasť"); LSTR MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); + LSTR MSG_MESH_CANCEL = _UxGT("Mriežka zrušená"); LSTR MSG_CUSTOM_COMMANDS = _UxGT("Vlastné príkazy"); LSTR MSG_M48_TEST = _UxGT("M48 Test sondy"); LSTR MSG_M48_POINT = _UxGT("M48 Bod"); @@ -182,6 +200,9 @@ namespace Language_sk { LSTR MSG_UBL_TOOLS = _UxGT("Nástroje UBL"); LSTR MSG_UBL_LEVEL_BED = _UxGT("UBL rovnanie"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Vyrovnávam bod"); + LSTR MSG_UBL_TILT_MESH = _UxGT("Nakloniť sieť"); + LSTR MSG_UBL_TILTING_GRID = _UxGT("Veľkosť nakl. siete"); + LSTR MSG_UBL_MESH_TILTED = _UxGT("Sieť naklonená"); LSTR MSG_UBL_MANUAL_MESH = _UxGT("Manuálna sieť bodov"); LSTR MSG_UBL_MESH_WIZARD = _UxGT("Spriev. UBL rovnan."); LSTR MSG_UBL_BC_INSERT = _UxGT("Položte a zmerajte"); @@ -230,6 +251,7 @@ namespace Language_sk { LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Ručné vyplnenie"); LSTR MSG_UBL_SMART_FILLIN = _UxGT("Chytré vyplnenie"); LSTR MSG_UBL_FILLIN_MESH = _UxGT("Vyplniť mriežku"); + LSTR MSG_UBL_MESH_FILLED = _UxGT("Doplnené chýb. body"); LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Zrušiť všetko"); LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Zrušiť najbližší"); LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Upraviť všetky"); @@ -238,6 +260,7 @@ namespace Language_sk { LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Pamäťový slot"); LSTR MSG_UBL_LOAD_MESH = _UxGT("Načítať sieť bodov"); LSTR MSG_UBL_SAVE_MESH = _UxGT("Uložiť sieť bodov"); + LSTR MSG_UBL_INVALID_SLOT = _UxGT("Najskôr zvol. slot siete"); LSTR MSG_MESH_LOADED = _UxGT("Sieť %i načítaná"); LSTR MSG_MESH_SAVED = _UxGT("Sieť %i uložená"); LSTR MSG_UBL_NO_STORAGE = _UxGT("Nedostatok miesta"); @@ -282,13 +305,11 @@ namespace Language_sk { LSTR MSG_MOVE_X = _UxGT("Posunúť X"); LSTR MSG_MOVE_Y = _UxGT("Posunúť Y"); LSTR MSG_MOVE_Z = _UxGT("Posunúť Z"); - LSTR MSG_MOVE_I = _UxGT("Posunúť ") STR_I; - LSTR MSG_MOVE_J = _UxGT("Posunúť ") STR_J; - LSTR MSG_MOVE_K = _UxGT("Posunúť ") STR_K; + LSTR MSG_MOVE_N = _UxGT("Posunúť @"); LSTR MSG_MOVE_E = _UxGT("Extrudér"); LSTR MSG_MOVE_EN = _UxGT("Extrudér *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); - LSTR MSG_MOVE_N_MM = _UxGT("Posunúť o %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Posunúť o $mm"); LSTR MSG_MOVE_01MM = _UxGT("Posunúť o 0,1mm"); LSTR MSG_MOVE_1MM = _UxGT("Posunúť o 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Posunúť o 10mm"); @@ -298,12 +319,6 @@ namespace Language_sk { LSTR MSG_MOVE_01IN = _UxGT("Posunúť o 0,1in"); LSTR MSG_MOVE_1IN = _UxGT("Posunúť o 1,0in"); LSTR MSG_SPEED = _UxGT("Rýchlosť"); - LSTR MSG_MAXSPEED = _UxGT("Max rýchl. (mm/s)"); - LSTR MSG_MAXSPEED_X = _UxGT("Max rýchl. ") STR_A; - LSTR MSG_MAXSPEED_Y = _UxGT("Max rýchl. ") STR_B; - LSTR MSG_MAXSPEED_Z = _UxGT("Max rýchl. ") STR_C; - LSTR MSG_MAXSPEED_E = _UxGT("Max rýchl. ") STR_E; - LSTR MSG_MAXSPEED_A = _UxGT("Max rýchl. @"); LSTR MSG_BED_Z = _UxGT("Výška podl."); LSTR MSG_NOZZLE = _UxGT("Tryska"); LSTR MSG_NOZZLE_N = _UxGT("Tryska ~"); @@ -338,9 +353,21 @@ namespace Language_sk { LSTR MSG_PID_AUTOTUNE_E = _UxGT("Kalibrácia PID *"); LSTR MSG_PID_CYCLE = _UxGT("Cykly PID"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Kal. PID dokončená"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-kal. zlyhala. Zlý extrúder."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-kal. zlyhala. Príliš vysoká tepl."); + LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("Kal. PID zlyhala!"); + LSTR MSG_BAD_EXTRUDER_NUM = _UxGT("Zlý extrudér"); + LSTR MSG_TEMP_TOO_HIGH = _UxGT("Príliš vysoká tepl."); + LSTR MSG_TIMEOUT = _UxGT("Čas vypršal."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-kal. zlyhala! Zlý extrúder."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-kal. zlyhala! Príliš vysoká tepl."); LSTR MSG_PID_TIMEOUT = _UxGT("Auto-kal. zlyhala! Čas vypršal."); + LSTR MSG_MPC_MEASURING_AMBIENT = _UxGT("Test. tepl. straty"); + LSTR MSG_MPC_AUTOTUNE = _UxGT("Auto-kal. MPC"); + LSTR MSG_MPC_EDIT = _UxGT("Upraviť * MPC"); + LSTR MSG_MPC_POWER_E = _UxGT("Výkon *"); + LSTR MSG_MPC_BLOCK_HEAT_CAPACITY_E = _UxGT("Blokovať C *"); + LSTR MSG_SENSOR_RESPONSIVENESS_E = _UxGT("Rozliš. senz. *"); + LSTR MSG_MPC_AMBIENT_XFER_COEFF_E = _UxGT("H okolia *"); + LSTR MSG_MPC_AMBIENT_XFER_COEFF_FAN_E = _UxGT("H vent. okolia *"); LSTR MSG_SELECT = _UxGT("Vybrať"); LSTR MSG_SELECT_E = _UxGT("Vybrať *"); LSTR MSG_ACC = _UxGT("Zrýchlenie"); @@ -348,30 +375,24 @@ namespace Language_sk { LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-skok"); LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-skok"); LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-skok"); - LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-skok"); - LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-skok"); - LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-skok"); + LSTR MSG_VN_JERK = _UxGT("V@-skok"); LSTR MSG_VE_JERK = _UxGT("Ve-skok"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); - LSTR MSG_VELOCITY = _UxGT("Rýchlosť"); - LSTR MSG_VMAX_A = _UxGT("Vmax ") STR_A; - LSTR MSG_VMAX_B = _UxGT("Vmax ") STR_B; - LSTR MSG_VMAX_C = _UxGT("Vmax ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Vmax ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Vmax ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Vmax ") STR_K; - LSTR MSG_VMAX_E = _UxGT("Vmax ") STR_E; - LSTR MSG_VMAX_EN = _UxGT("Vmax *"); + LSTR MSG_MAX_SPEED = _UxGT("Max rýchl. (mm/s)"); + LSTR MSG_VMAX_A = _UxGT("Max rýchl. ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Max rýchl. ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Max rýchl. ") STR_C; + LSTR MSG_VMAX_N = _UxGT("Max rýchl. @"); + LSTR MSG_VMAX_E = _UxGT("Max rýchl. E"); + LSTR MSG_VMAX_EN = _UxGT("Max rýchl. *"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VPrej Min"); LSTR MSG_ACCELERATION = _UxGT("Akcelerácia"); LSTR MSG_AMAX_A = _UxGT("Amax ") STR_A; LSTR MSG_AMAX_B = _UxGT("Amax ") STR_B; LSTR MSG_AMAX_C = _UxGT("Amax ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Amax ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Amax ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Amax ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Amax ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Amax @"); + LSTR MSG_AMAX_E = _UxGT("Amax E"); LSTR MSG_AMAX_EN = _UxGT("Amax *"); LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); LSTR MSG_A_TRAVEL = _UxGT("A-prejazd"); @@ -381,11 +402,9 @@ namespace Language_sk { LSTR MSG_A_STEPS = STR_A _UxGT(" krokov/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" krokov/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" krokov/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" krokov/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" krokov/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" krokov/mm"); - LSTR MSG_E_STEPS = _UxGT("Ekrokov/mm"); - LSTR MSG_EN_STEPS = _UxGT("*krokov/mm"); + LSTR MSG_N_STEPS = _UxGT("@ krokov/mm"); + LSTR MSG_E_STEPS = _UxGT("E krokov/mm"); + LSTR MSG_EN_STEPS = _UxGT("* krokov/mm"); LSTR MSG_TEMPERATURE = _UxGT("Teplota"); LSTR MSG_MOTION = _UxGT("Pohyb"); LSTR MSG_FILAMENT = _UxGT("Filament"); @@ -400,6 +419,9 @@ namespace Language_sk { LSTR MSG_ADVANCE_K_E = _UxGT("K pre posun *"); LSTR MSG_CONTRAST = _UxGT("Kontrast LCD"); LSTR MSG_BRIGHTNESS = _UxGT("Jas LCD"); + LSTR MSG_LCD_TIMEOUT_SEC = _UxGT("Čas. limit LCD (s)"); + LSTR MSG_SCREEN_TIMEOUT = _UxGT("Čas. limit LCD (m)"); + LSTR MSG_BRIGHTNESS_OFF = _UxGT("Podsviet. vyp."); LSTR MSG_STORE_EEPROM = _UxGT("Uložiť nastavenie"); LSTR MSG_LOAD_EEPROM = _UxGT("Načítať nastavenie"); LSTR MSG_RESTORE_DEFAULTS = _UxGT("Obnoviť nastavenie"); @@ -412,6 +434,10 @@ namespace Language_sk { LSTR MSG_RESET_PRINTER = _UxGT("Reštart. tlačiar."); LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Obnoviť"); LSTR MSG_INFO_SCREEN = _UxGT("Info. obrazovka"); + LSTR MSG_INFO_MACHINENAME = _UxGT("Názov stroja"); + LSTR MSG_INFO_SIZE = _UxGT("Rozmer"); + LSTR MSG_INFO_FWVERSION = _UxGT("Verzia firmvéru"); + LSTR MSG_INFO_BUILD = _UxGT("Čas zostavenia"); LSTR MSG_PREPARE = _UxGT("Príprava tlače"); LSTR MSG_TUNE = _UxGT("Doladenie tlače"); LSTR MSG_POWER_MONITOR = _UxGT("Monitor napájania"); @@ -426,6 +452,8 @@ namespace Language_sk { LSTR MSG_BUTTON_RESET = _UxGT("Vynulovať"); LSTR MSG_BUTTON_IGNORE = _UxGT("Ignorovať"); LSTR MSG_BUTTON_CANCEL = _UxGT("Zrušiť"); + LSTR MSG_BUTTON_CONFIRM = _UxGT("Potvrdiť"); + LSTR MSG_BUTTON_CONTINUE = _UxGT("Pokračovať"); LSTR MSG_BUTTON_DONE = _UxGT("Hotovo"); LSTR MSG_BUTTON_BACK = _UxGT("Naspäť"); LSTR MSG_BUTTON_PROCEED = _UxGT("Pokračovať"); @@ -435,6 +463,8 @@ namespace Language_sk { LSTR MSG_BUTTON_PAUSE = _UxGT("Pauza"); LSTR MSG_BUTTON_RESUME = _UxGT("Obnoviť"); LSTR MSG_BUTTON_ADVANCED = _UxGT("Pokročilé"); + LSTR MSG_BUTTON_SAVE = _UxGT("Uložiť"); + LSTR MSG_BUTTON_PURGE = _UxGT("Vytlačiť"); LSTR MSG_PAUSING = _UxGT("Pozastavujem..."); LSTR MSG_PAUSE_PRINT = _UxGT("Pozastaviť tlač"); LSTR MSG_ADVANCED_PAUSE = _UxGT("Pokročil. pauza"); @@ -454,11 +484,15 @@ namespace Language_sk { LSTR MSG_PRINT_PAUSED = _UxGT("Tlač pozastavená"); LSTR MSG_PRINTING = _UxGT("Tlačím..."); LSTR MSG_STOPPING = _UxGT("Zastavujem..."); + LSTR MSG_REMAINING_TIME = _UxGT("Zostávajúci"); LSTR MSG_PRINT_ABORTED = _UxGT("Tlač zrušená"); LSTR MSG_PRINT_DONE = _UxGT("Tlač dokončená"); + LSTR MSG_PRINTER_KILLED = _UxGT("Tlačiareň zastavená!"); + LSTR MSG_TURN_OFF = _UxGT("Vypnite tlačiareň"); LSTR MSG_NO_MOVE = _UxGT("Žiadny pohyb."); LSTR MSG_KILLED = _UxGT("PRERUŠENÉ. "); LSTR MSG_STOPPED = _UxGT("ZASTAVENÉ. "); + LSTR MSG_FWRETRACT = _UxGT("Firmv. retrakcia"); LSTR MSG_CONTROL_RETRACT = _UxGT("Retrakt mm"); LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Výmena Re.mm"); LSTR MSG_CONTROL_RETRACTF = _UxGT("Retraktovať V"); @@ -524,13 +558,14 @@ namespace Language_sk { LSTR MSG_ZPROBE_XOFFSET = _UxGT("X ofset"); LSTR MSG_ZPROBE_YOFFSET = _UxGT("Y ofset"); LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z ofset"); + LSTR MSG_ZPROBE_MARGIN = _UxGT("Hranica sondy"); + LSTR MSG_Z_FEED_RATE = _UxGT("Rýchl. posunu Z"); + LSTR MSG_ENABLE_HS_MODE = _UxGT("Povoliť rež. HS"); LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Pos. trysku k podl."); LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; + LSTR MSG_BABYSTEP_N = _UxGT("Babystep @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Celkom"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Zastavenie Endstop"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Chyba ohrevu"); @@ -563,8 +598,6 @@ namespace Language_sk { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrovať stred"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta nastavenia"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto-kalibrácia"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Nast. výšku delty"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Ofset sondy Z"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag. rameno"); LSTR MSG_DELTA_HEIGHT = _UxGT("Výška"); LSTR MSG_DELTA_RADIUS = _UxGT("Polomer"); @@ -591,30 +624,32 @@ namespace Language_sk { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas svetla"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Nesprávna tlačiareň"); + LSTR MSG_COLORS_GET = _UxGT("Zvoliť farbu"); + LSTR MSG_COLORS_SELECT = _UxGT("Zvoliť farby"); + LSTR MSG_COLORS_APPLIED = _UxGT("Farby aplikované"); + LSTR MSG_COLORS_RED = _UxGT("Červená"); + LSTR MSG_COLORS_GREEN = _UxGT("Zelená"); + LSTR MSG_COLORS_BLUE = _UxGT("Modrá"); + LSTR MSG_COLORS_WHITE = _UxGT("Biela"); + LSTR MSG_UI_LANGUAGE = _UxGT("Jazyk rozhrania"); + LSTR MSG_SOUND_ENABLE = _UxGT("Povoliť zvuky"); + LSTR MSG_LOCKSCREEN = _UxGT("Uzamknúť obrazovku"); + LSTR MSG_LOCKSCREEN_LOCKED = _UxGT("Tlačiareň je uzamknutá,"); + LSTR MSG_LOCKSCREEN_UNLOCK = _UxGT("potiahnite pre odomknutie."); + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Prosím čakajte do reštartu."); + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Nie je vložená karta."); - LSTR MSG_REMAINING_TIME = _UxGT("Zostávajúci čas"); - LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Prosím čakajte do reštartu. "); LSTR MSG_PLEASE_PREHEAT = _UxGT("Prosím zahrejte hotend."); LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Vynulovať počítadlo"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Počet tlačí"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Celkový čas"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najdlhšia tlač"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Celkom vytlačené"); - LSTR MSG_COLORS_GET = _UxGT("Zvoliť farbu"); - LSTR MSG_COLORS_SELECT = _UxGT("Zvoliť farby"); - LSTR MSG_COLORS_APPLIED = _UxGT("Farby aplikované"); - LSTR MSG_COLORS_RED = _UxGT("Červená"); - LSTR MSG_COLORS_GREEN = _UxGT("Zelená"); - LSTR MSG_COLORS_BLUE = _UxGT("Modrá"); - LSTR MSG_UI_LANGUAGE = _UxGT("Jazyk rozhrania"); - LSTR MSG_SOUND_ENABLE = _UxGT("Povoliť zvuky"); - LSTR MSG_LOCKSCREEN = _UxGT("Uzamknúť obrazovku"); #else LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Žiadna karta"); LSTR MSG_PLEASE_PREHEAT = _UxGT("Prosím zahrejte"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Tlače"); - LSTR MSG_REMAINING_TIME = _UxGT("Zostávajúci"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Čas"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najdlhšia"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Vytlačené"); @@ -625,13 +660,7 @@ namespace Language_sk { LSTR MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); LSTR MSG_INFO_PSU = _UxGT("Nap. zdroj"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Budenie motorov"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Motor %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Motor %"); LSTR MSG_ERROR_TMC = _UxGT("CHYBA KOMUNIKÁ. TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Uložiť do EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("VÝMENA FILAMENTU"); @@ -641,10 +670,14 @@ namespace Language_sk { LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("MOŽNOSTI POKRAČ.:"); LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Vytlačiť viacej"); LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Obnoviť tlač"); + LSTR MSG_FILAMENT_CHANGE_PURGE_CONTINUE = _UxGT("Vytlač. alebo pokrač.?"); LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Tryska: "); LSTR MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Vzd. mm fil. senz."); LSTR MSG_RUNOUT_ENABLE = _UxGT("Zapnúť senzor"); + LSTR MSG_RUNOUT_ACTIVE = _UxGT("Senz. fil. zapn."); + LSTR MSG_INVERT_EXTRUDER = _UxGT("Invert. extrudér"); + LSTR MSG_EXTRUDER_MIN_TEMP = _UxGT("Min. tepl. extrud."); LSTR MSG_FANCHECK = _UxGT("Kontrola rýchl."); LSTR MSG_KILL_HOMING_FAILED = _UxGT("Parkovanie zlyhalo"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Kalibrácia zlyhala"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index 744fb7e3e603..6bfb7100f4ef 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -73,7 +73,6 @@ namespace Language_sv { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Falna Höjd"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Sätt Hem Offset"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset Tillämpad"); - LSTR MSG_SET_ORIGIN = _UxGT("Sätt Origo"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Justerings Wizard"); LSTR MSG_SELECT_ORIGIN = _UxGT("Välj Origo"); LSTR MSG_LAST_VALUE_SP = _UxGT("Senaste värde "); @@ -253,7 +252,7 @@ namespace Language_sv { LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hetände för kall"); - LSTR MSG_MOVE_N_MM = _UxGT("Flytta %smm"); + LSTR MSG_MOVE_N_MM = _UxGT("Flytta $mm"); LSTR MSG_MOVE_01MM = _UxGT("Flytta 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Flytta 1mm"); LSTR MSG_MOVE_10MM = _UxGT("Flytta 10mm"); @@ -291,8 +290,8 @@ namespace Language_sv { LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autojustera"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autojustera *"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autojustera misslyckad. Dålig extruder."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autojustera misslyckad. Temperatur för hög."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autojustera misslyckad! Dålig extruder."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autojustera misslyckad! Temperatur för hög."); LSTR MSG_PID_TIMEOUT = _UxGT("Autojustera misslyckad! Tidsgräns."); LSTR MSG_SELECT = _UxGT("Välj"); LSTR MSG_SELECT_E = _UxGT("Välj *"); @@ -301,19 +300,15 @@ namespace Language_sv { LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-Ryck"); LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-Ryck"); LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-Ryck"); - LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-Ryck"); - LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-Ryck"); - LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-Ryck"); + LSTR MSG_VN_JERK = _UxGT("V@-Ryck"); LSTR MSG_VE_JERK = _UxGT("Ve-Ryck"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Knutpunkt Avv"); - LSTR MSG_VELOCITY = _UxGT("Hastighet"); + LSTR MSG_MAX_SPEED = _UxGT("Hastighet"); LSTR MSG_VMAX_A = _UxGT("Vmax ") STR_A; LSTR MSG_VMAX_B = _UxGT("Vmax ") STR_B; LSTR MSG_VMAX_C = _UxGT("Vmax ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Vmax ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Vmax ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Vmax ") STR_K; - LSTR MSG_VMAX_E = _UxGT("Vmax ") STR_E; + LSTR MSG_VMAX_N = _UxGT("Vmax @"); + LSTR MSG_VMAX_E = _UxGT("Vmax E"); LSTR MSG_VMAX_EN = _UxGT("Vmax *"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); @@ -321,10 +316,8 @@ namespace Language_sv { LSTR MSG_AMAX_A = _UxGT("Amax ") STR_A; LSTR MSG_AMAX_B = _UxGT("Amax ") STR_B; LSTR MSG_AMAX_C = _UxGT("Amax ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Amax ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Amax ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Amax ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Amax ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Amax @"); + LSTR MSG_AMAX_E = _UxGT("Amax E"); LSTR MSG_AMAX_EN = _UxGT("Amax *"); LSTR MSG_A_RETRACT = _UxGT("A-Dra tillbaka"); LSTR MSG_A_TRAVEL = _UxGT("A-Färdas"); @@ -334,9 +327,7 @@ namespace Language_sv { LSTR MSG_A_STEPS = STR_A _UxGT(" Steg/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" Steg/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" Steg/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" Steg/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" Steg/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" Steg/mm"); + LSTR MSG_N_STEPS = _UxGT("@ Steg/mm"); LSTR MSG_E_STEPS = _UxGT("E Steg/mm"); LSTR MSG_EN_STEPS = _UxGT("* Steg/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatur"); @@ -470,6 +461,7 @@ namespace Language_sv { LSTR MSG_BABYSTEP_X = _UxGT("Småsteg X"); LSTR MSG_BABYSTEP_Y = _UxGT("Småsteg Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Småsteg Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Småsteg @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Slutstopp Avbrott"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Värma Misslyckad"); @@ -497,8 +489,6 @@ namespace Language_sv { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrera Center"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Inställningar"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibrering"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Sätt Delta Höjd"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Sond Z-offset"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); LSTR MSG_DELTA_HEIGHT = _UxGT("Höjd"); LSTR MSG_DELTA_RADIUS = _UxGT("Radius"); @@ -541,13 +531,7 @@ namespace Language_sv { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); LSTR MSG_INFO_PSU = _UxGT("PSU"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Driv Styrka"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Driver %"); LSTR MSG_ERROR_TMC = _UxGT("TMC KOPPLNINGSFEL"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("TRÅDBYTE"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 8a1864c96647..c9967f72ec2d 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -72,7 +72,6 @@ namespace Language_tr { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Kaçınma Yüksekliği"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ofset Ayarla"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofset Tamam"); - LSTR MSG_SET_ORIGIN = _UxGT("Sıfır Belirle"); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Ön Isınma ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Ön Isınma ") PREHEAT_1_LABEL " ~"; @@ -229,7 +228,7 @@ namespace Language_tr { LSTR MSG_MOVE_E = _UxGT("Ekstruder"); LSTR MSG_MOVE_EN = _UxGT("Ekstruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Nozul Çok Soğuk"); - LSTR MSG_MOVE_N_MM = _UxGT("%smm"); + LSTR MSG_MOVE_N_MM = _UxGT("$mm"); LSTR MSG_MOVE_01MM = _UxGT("0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("1mm"); LSTR MSG_MOVE_10MM = _UxGT("10mm"); @@ -264,19 +263,15 @@ namespace Language_tr { LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-Sarsım"); LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-Sarsım"); LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-Sarsım"); - LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-Sarsım"); - LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-Sarsım"); - LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-Sarsım"); + LSTR MSG_VN_JERK = _UxGT("V@-Sarsım"); LSTR MSG_VE_JERK = _UxGT("Ve-Sarsım"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Jonksiyon Sapması"); - LSTR MSG_VELOCITY = _UxGT("Hız Vektörü"); + LSTR MSG_MAX_SPEED = _UxGT("Hız Vektörü"); LSTR MSG_VMAX_A = _UxGT("HızVektör.max ") STR_A; LSTR MSG_VMAX_B = _UxGT("HızVektör.max ") STR_B; LSTR MSG_VMAX_C = _UxGT("HızVektör.max ") STR_C; - LSTR MSG_VMAX_I = _UxGT("HızVektör.max ") STR_I; - LSTR MSG_VMAX_J = _UxGT("HızVektör.max ") STR_J; - LSTR MSG_VMAX_K = _UxGT("HızVektör.max ") STR_K; - LSTR MSG_VMAX_E = _UxGT("HızVektör.max ") STR_E; + LSTR MSG_VMAX_N = _UxGT("HızVektör.max @"); + LSTR MSG_VMAX_E = _UxGT("HızVektör.max E"); LSTR MSG_VMAX_EN = _UxGT("HızVektör.max *"); LSTR MSG_VMIN = _UxGT("HızVektör.min"); LSTR MSG_VTRAV_MIN = _UxGT("HV.gezinme min"); @@ -284,10 +279,8 @@ namespace Language_tr { LSTR MSG_AMAX_A = _UxGT("Max. ivme ") STR_A; LSTR MSG_AMAX_B = _UxGT("Max. ivme ") STR_B; LSTR MSG_AMAX_C = _UxGT("Max. ivme ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Max. ivme ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Max. ivme ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Max. ivme ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Max. ivme ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Max. ivme @"); + LSTR MSG_AMAX_E = _UxGT("Max. ivme E"); LSTR MSG_AMAX_EN = _UxGT("Max. ivme *"); LSTR MSG_A_RETRACT = _UxGT("Ivme-geri çekme"); LSTR MSG_A_TRAVEL = _UxGT("Ivme-gezinme"); @@ -295,9 +288,7 @@ namespace Language_tr { LSTR MSG_A_STEPS = STR_A _UxGT(" adım/mm"); LSTR MSG_B_STEPS = STR_B _UxGT(" adım/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" adım/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" adım/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" adım/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" adım/mm"); + LSTR MSG_N_STEPS = _UxGT("@ adım/mm"); LSTR MSG_E_STEPS = _UxGT("E adım/mm"); LSTR MSG_EN_STEPS = _UxGT("* adım/mm"); LSTR MSG_TEMPERATURE = _UxGT("Sıcaklık"); @@ -407,6 +398,7 @@ namespace Language_tr { LSTR MSG_BABYSTEP_X = _UxGT("Miniadım X"); LSTR MSG_BABYSTEP_Y = _UxGT("Miniadım Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Miniadım Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Miniadım @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Toplam"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop iptal"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Isınma başarısız"); @@ -434,8 +426,6 @@ namespace Language_tr { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Ayarla Merkez"); LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Ayarları"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Oto Kalibrasyon"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Yük. Ayarla"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z Prob Ofseti"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Çapral Mil"); LSTR MSG_DELTA_HEIGHT = _UxGT("Yükseklik"); LSTR MSG_DELTA_RADIUS = _UxGT("Yarıçap"); @@ -474,13 +464,7 @@ namespace Language_tr { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Sıc."); LSTR MSG_INFO_PSU = _UxGT("Güç Kaynağı"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Sürücü Gücü"); - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E Sürücü %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ Sürücü %"); LSTR MSG_ERROR_TMC = _UxGT("TMC BAĞLANTI HATASI"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Yaz"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMAN DEGISTIR"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index b67c21f25f7c..6170faedaeea 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -86,20 +86,13 @@ namespace Language_uk { LSTR MSG_HOME_OFFSET_X = _UxGT("Зміщення дому X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Зміщення дому Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Зміщення дому Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Зміщення дому ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Зміщення дому ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Зміщення дому ") STR_K; #else LSTR MSG_SET_HOME_OFFSETS = _UxGT("Встан. зміщ. дому"); LSTR MSG_HOME_OFFSET_X = _UxGT("Зміщ. дому X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Зміщ. дому Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Зміщ. дому Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Зміщ. дому ") STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Зміщ. дому ") STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Зміщ. дому ") STR_K; #endif LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Зміщення прийняті"); - LSTR MSG_SET_ORIGIN = _UxGT("Встановити нуль"); LSTR MSG_SELECT_ORIGIN = _UxGT("Оберіть нуль"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_LAST_VALUE_SP = _UxGT("Останнє значення "); @@ -340,9 +333,7 @@ namespace Language_uk { LSTR MSG_MOVE_X = _UxGT("Рух по X"); LSTR MSG_MOVE_Y = _UxGT("Рух по Y"); LSTR MSG_MOVE_Z = _UxGT("Рух по Z"); - LSTR MSG_MOVE_I = _UxGT("Рух по ") STR_I; - LSTR MSG_MOVE_J = _UxGT("Рух по ") STR_J; - LSTR MSG_MOVE_K = _UxGT("Рух по ") STR_K; + LSTR MSG_MOVE_N = _UxGT("Рух по @"); LSTR MSG_MOVE_E = _UxGT("Екструдер"); LSTR MSG_MOVE_EN = _UxGT("Екструдер *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Сопло дуже холодне"); @@ -396,8 +387,8 @@ namespace Language_uk { LSTR MSG_PID_AUTOTUNE = _UxGT("Автопідбір PID"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("Автопідбір PID *"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Підбір PID виконано"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Збій автопідбору. Поганий екструдер."); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Збій автопідбору. Температура завищена."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Збій автопідбору! Поганий екструдер."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Збій автопідбору! Температура завищена."); LSTR MSG_PID_TIMEOUT = _UxGT("Збій автопідбору! Вичерпан час."); LSTR MSG_SELECT = _UxGT("Вибрати"); @@ -407,23 +398,19 @@ namespace Language_uk { LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-ривок"); LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-ривок"); LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-ривок"); - LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-ривок"); - LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-ривок"); - LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-ривок"); + LSTR MSG_VN_JERK = _UxGT("V@-ривок"); LSTR MSG_VE_JERK = _UxGT("Ve-ривок"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_JUNCTION_DEVIATION = _UxGT("Відхилення вузла"); #else LSTR MSG_JUNCTION_DEVIATION = _UxGT("Відхил.вузла"); #endif - LSTR MSG_VELOCITY = _UxGT("Швидкість, мм/с"); + LSTR MSG_MAX_SPEED = _UxGT("Швидкість, мм/с"); LSTR MSG_VMAX_A = _UxGT("Швидк.макс ") STR_A; LSTR MSG_VMAX_B = _UxGT("Швидк.макс ") STR_B; LSTR MSG_VMAX_C = _UxGT("Швидк.макс ") STR_C; - LSTR MSG_VMAX_I = _UxGT("Швидк.макс ") STR_I; - LSTR MSG_VMAX_J = _UxGT("Швидк.макс ") STR_J; - LSTR MSG_VMAX_K = _UxGT("Швидк.макс ") STR_K; - LSTR MSG_VMAX_E = _UxGT("Швидк.макс ") STR_E; + LSTR MSG_VMAX_N = _UxGT("Швидк.макс @"); + LSTR MSG_VMAX_E = _UxGT("Швидк.макс E"); LSTR MSG_VMAX_EN = _UxGT("Швидк.макс *"); LSTR MSG_VMIN = _UxGT("Швидк. мін"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 @@ -435,10 +422,8 @@ namespace Language_uk { LSTR MSG_AMAX_A = _UxGT("Приск.макс ") STR_A; LSTR MSG_AMAX_B = _UxGT("Приск.макс ") STR_B; LSTR MSG_AMAX_C = _UxGT("Приск.макс ") STR_C; - LSTR MSG_AMAX_I = _UxGT("Приск.макс ") STR_I; - LSTR MSG_AMAX_J = _UxGT("Приск.макс ") STR_J; - LSTR MSG_AMAX_K = _UxGT("Приск.макс ") STR_K; - LSTR MSG_AMAX_E = _UxGT("Приск.макс ") STR_E; + LSTR MSG_AMAX_N = _UxGT("Приск.макс @"); + LSTR MSG_AMAX_E = _UxGT("Приск.макс E"); LSTR MSG_AMAX_EN = _UxGT("Приск.макс *"); LSTR MSG_A_RETRACT = _UxGT("Приск.втягув."); LSTR MSG_A_TRAVEL = _UxGT("Приск.переміщ."); @@ -448,9 +433,7 @@ namespace Language_uk { LSTR MSG_A_STEPS = STR_A _UxGT(" кроків/мм"); LSTR MSG_B_STEPS = STR_B _UxGT(" кроків/мм"); LSTR MSG_C_STEPS = STR_C _UxGT(" кроків/мм"); - LSTR MSG_I_STEPS = STR_I _UxGT(" кроків/мм"); - LSTR MSG_J_STEPS = STR_J _UxGT(" кроків/мм"); - LSTR MSG_K_STEPS = STR_K _UxGT(" кроків/мм"); + LSTR MSG_N_STEPS = _UxGT("@ кроків/мм"); LSTR MSG_E_STEPS = _UxGT("E кроків/мм"); LSTR MSG_EN_STEPS = _UxGT("* кроків/мм"); LSTR MSG_TEMPERATURE = _UxGT("Температура"); @@ -625,9 +608,7 @@ namespace Language_uk { LSTR MSG_BABYSTEP_X = _UxGT("Мікрокрок X"); LSTR MSG_BABYSTEP_Y = _UxGT("Мікрокрок Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Мікрокрок Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Мікрокрок ") STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Мікрокрок ") STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Мікрокрок ") STR_K; + LSTR MSG_BABYSTEP_N = _UxGT("Мікрокрок @"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Кінцевик спрацював"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Збій нагріву"); @@ -671,8 +652,6 @@ namespace Language_uk { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калібр. центр"); LSTR MSG_DELTA_SETTINGS = _UxGT("Параметри Delta"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Автокалібрування"); - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Встан. Висоту Delta"); - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z-зміщення зонду"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("Діагональ стрижня"); LSTR MSG_DELTA_HEIGHT = _UxGT("Висота"); LSTR MSG_DELTA_RADIUS = _UxGT("Радіус"); @@ -750,13 +729,7 @@ namespace Language_uk { LSTR MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; LSTR MSG_INFO_PSU = _UxGT("Блок жив-ня"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Сила мотору"); - LSTR MSG_DAC_PERCENT_A = _UxGT("Драйвер ") STR_A _UxGT(", %"); - LSTR MSG_DAC_PERCENT_B = _UxGT("Драйвер ") STR_B _UxGT(", %"); - LSTR MSG_DAC_PERCENT_C = _UxGT("Драйвер ") STR_C _UxGT(", %"); - LSTR MSG_DAC_PERCENT_I = _UxGT("Драйвер ") STR_I _UxGT(", %"); - LSTR MSG_DAC_PERCENT_J = _UxGT("Драйвер ") STR_J _UxGT(", %"); - LSTR MSG_DAC_PERCENT_K = _UxGT("Драйвер ") STR_K _UxGT(", %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); + LSTR MSG_DAC_PERCENT_N = _UxGT("Драйвер @, %"); LSTR MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("ЗАМІНА ПРУТКА"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 879ccdeae7c6..989a201d4d92 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -63,7 +63,6 @@ namespace Language_vi { LSTR MSG_Z_FADE_HEIGHT = _UxGT("Chiều cao mờ dần"); // Fade Height LSTR MSG_SET_HOME_OFFSETS = _UxGT("Đặt bù đắp nhà"); // Set home offsets LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Bù đắp được áp dụng"); // Offsets applied - LSTR MSG_SET_ORIGIN = _UxGT("Đặt nguồn gốc"); // Set origin #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" trước"); // Preheat LSTR MSG_PREHEAT_1_H = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" trước ~"); // Preheat @@ -231,19 +230,15 @@ namespace Language_vi { LSTR MSG_VA_JERK = _UxGT("Giật-V") STR_A; LSTR MSG_VB_JERK = _UxGT("Giật-V") STR_B; LSTR MSG_VC_JERK = _UxGT("Giật-V") STR_C; - LSTR MSG_VI_JERK = _UxGT("Giật-V") STR_I; - LSTR MSG_VJ_JERK = _UxGT("Giật-V") STR_J; - LSTR MSG_VK_JERK = _UxGT("Giật-V") STR_K; + LSTR MSG_VN_JERK = _UxGT("Giật-V@"); LSTR MSG_VE_JERK = _UxGT("Giật-Ve"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Độ Lệch Chỗ Giao"); // Junction Dev - LSTR MSG_VELOCITY = _UxGT("Vận tốc"); // velocity + LSTR MSG_MAX_SPEED = _UxGT("Vận tốc"); // velocity LSTR MSG_VMAX_A = _UxGT("Vđa") STR_A; // Vmax LSTR MSG_VMAX_B = _UxGT("Vđa") STR_B; LSTR MSG_VMAX_C = _UxGT("Vđa") STR_C; - LSTR MSG_VMAX_I = _UxGT("Vđa") STR_I; - LSTR MSG_VMAX_J = _UxGT("Vđa") STR_J; - LSTR MSG_VMAX_K = _UxGT("Vđa") STR_K; - LSTR MSG_VMAX_E = _UxGT("Vđa") STR_E; + LSTR MSG_VMAX_N = _UxGT("Vđa@"); + LSTR MSG_VMAX_E = _UxGT("VđaE"); LSTR MSG_VMAX_EN = _UxGT("Vđa *"); LSTR MSG_VMIN = _UxGT("Vthiểu"); // Vmin LSTR MSG_VTRAV_MIN = _UxGT("Vchuyển thiểu"); // VTrav min @@ -251,10 +246,8 @@ namespace Language_vi { LSTR MSG_AMAX_A = _UxGT("Tăng tốc ca") STR_A; // Amax LSTR MSG_AMAX_B = _UxGT("Tăng tốc ca") STR_B; LSTR MSG_AMAX_C = _UxGT("Tăng tốc ca") STR_C; - LSTR MSG_AMAX_I = _UxGT("Tăng tốc ca") STR_I; // Amax - LSTR MSG_AMAX_J = _UxGT("Tăng tốc ca") STR_J; - LSTR MSG_AMAX_K = _UxGT("Tăng tốc ca") STR_K; - LSTR MSG_AMAX_E = _UxGT("Tăng tốc ca") STR_E; + LSTR MSG_AMAX_N = _UxGT("Tăng tốc ca@"); + LSTR MSG_AMAX_E = _UxGT("Tăng tốc caE"); LSTR MSG_AMAX_EN = _UxGT("Tăng tốc ca *"); LSTR MSG_A_RETRACT = _UxGT("TT-Rút"); // A-retract LSTR MSG_A_TRAVEL = _UxGT("TT-Chuyển"); // A-travel @@ -262,9 +255,7 @@ namespace Language_vi { LSTR MSG_A_STEPS = _UxGT("Bước") STR_A _UxGT("/mm"); // Steps/mm LSTR MSG_B_STEPS = _UxGT("Bước") STR_B _UxGT("/mm"); LSTR MSG_C_STEPS = _UxGT("Bước") STR_C _UxGT("/mm"); - LSTR MSG_I_STEPS = _UxGT("Bước") STR_I _UxGT("/mm"); // Steps/mm - LSTR MSG_J_STEPS = _UxGT("Bước") STR_J _UxGT("/mm"); - LSTR MSG_K_STEPS = _UxGT("Bước") STR_K _UxGT("/mm"); + LSTR MSG_N_STEPS = _UxGT("Bước@/mm"); LSTR MSG_E_STEPS = _UxGT("BướcE/mm"); LSTR MSG_EN_STEPS = _UxGT("Bước */mm"); LSTR MSG_TEMPERATURE = _UxGT("Nhiệt độ"); // Temperature @@ -340,6 +331,7 @@ namespace Language_vi { LSTR MSG_BABYSTEP_X = _UxGT("Nhít X"); // Babystep X LSTR MSG_BABYSTEP_Y = _UxGT("Nhít Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Nhít Z"); + LSTR MSG_BABYSTEP_N = _UxGT("Nhít @"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Hủy bỏ công tắc"); // Endstop abort LSTR MSG_HEATING_FAILED_LCD = _UxGT("Sưởi đầu phun không thành công"); // Heating failed LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Điều sai: nhiệt độ dư"); // Err: REDUNDANT TEMP @@ -363,8 +355,6 @@ namespace Language_vi { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Chỉnh Z Center"); // Calibrate Center LSTR MSG_DELTA_SETTINGS = _UxGT("Cài Đặt Delta"); // Delta Settings LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Cân Chỉnh Tự Động"); // Auto Calibration - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Đặt Chiều Cao Delta"); // Set Delta Height - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Đầu Dò Z-Bù Đắp"); // Probe Z-offset LSTR MSG_DELTA_DIAG_ROD = _UxGT("Gậy Chéo"); // Diag Rod LSTR MSG_DELTA_HEIGHT = _UxGT("Chiều Cao"); // Height LSTR MSG_DELTA_RADIUS = _UxGT("Bán Kính"); // Radius @@ -400,13 +390,7 @@ namespace Language_vi { LSTR MSG_INFO_MAX_TEMP = _UxGT("Nhiệt độ tối đa"); // Max temp LSTR MSG_INFO_PSU = _UxGT("Bộ nguồn"); // PSU LSTR MSG_DRIVE_STRENGTH = _UxGT("Sức mạnh ổ đĩa"); // Drive Strength - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" % trình điều khiển"); // X Driver % - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E % trình điều khiển"); + LSTR MSG_DAC_PERCENT_N = _UxGT("@ % trình điều khiển"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Ghi DAC EEPROM"); // DAC EEPROM Write LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("In tạm dừng"); // PRINT PAUSED LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("Nạp dây nhựa"); diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index ce5dcefaa401..fc61b020ffc2 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -68,7 +68,6 @@ namespace Language_zh_CN { LSTR MSG_Z_FADE_HEIGHT = _UxGT("淡出高度"); // "Fade Height" LSTR MSG_SET_HOME_OFFSETS = _UxGT("设置原点偏移"); // "Set home offsets" LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已启用"); // "Offsets applied" - LSTR MSG_SET_ORIGIN = _UxGT("设置原点"); // "Set origin" #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("预热 ") PREHEAT_1_LABEL; // "Preheat PREHEAT_2_LABEL" LSTR MSG_PREHEAT_1_H = _UxGT("预热 ") PREHEAT_1_LABEL " ~"; // "Preheat PREHEAT_2_LABEL" @@ -226,7 +225,7 @@ namespace Language_zh_CN { LSTR MSG_MOVE_E = _UxGT("挤出机"); // "Extruder" LSTR MSG_MOVE_EN = _UxGT("挤出机 *"); // "Extruder" LSTR MSG_HOTEND_TOO_COLD = _UxGT("热端太冷"); - LSTR MSG_MOVE_N_MM = _UxGT("移动 %s mm"); // "Move 0.025mm" + LSTR MSG_MOVE_N_MM = _UxGT("移动 $ mm"); // "Move 0.025mm" LSTR MSG_MOVE_01MM = _UxGT("移动 0.1 mm"); // "Move 0.1mm" LSTR MSG_MOVE_1MM = _UxGT("移动 1 mm"); // "Move 1mm" LSTR MSG_MOVE_10MM = _UxGT("移动 10 mm"); // "Move 10mm" @@ -261,8 +260,8 @@ namespace Language_zh_CN { LSTR MSG_PID_AUTOTUNE = _UxGT("自动PID"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("自动PID *"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID调整完成"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("自动调失败. 坏的挤出机"); - LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("自动调失败. 温度太高"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("自动调失败! 坏的挤出机"); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("自动调失败! 温度太高"); LSTR MSG_PID_TIMEOUT = _UxGT("自动调失败! 超时"); LSTR MSG_SELECT = _UxGT("选择"); // "Select" LSTR MSG_SELECT_E = _UxGT("选择 *"); @@ -271,19 +270,15 @@ namespace Language_zh_CN { LSTR MSG_VA_JERK = _UxGT("轴抖动速率") STR_A; // "Va-jerk" LSTR MSG_VB_JERK = _UxGT("轴抖动速率") STR_B; // "Vb-jerk" LSTR MSG_VC_JERK = _UxGT("轴抖动速率") STR_C; // "Vc-jerk" - LSTR MSG_VI_JERK = _UxGT("轴抖动速率") STR_I; // "Vi-jerk" - LSTR MSG_VJ_JERK = _UxGT("轴抖动速率") STR_J; // "Vj-jerk" - LSTR MSG_VK_JERK = _UxGT("轴抖动速率") STR_K; // "Vk-jerk" + LSTR MSG_VN_JERK = _UxGT("轴抖动速率@"); // "V@-jerk" LSTR MSG_VE_JERK = _UxGT("挤出机抖动速率"); // "Ve-jerk" LSTR MSG_JUNCTION_DEVIATION = _UxGT("接点差"); - LSTR MSG_VELOCITY = _UxGT("速度"); // "Velocity" + LSTR MSG_MAX_SPEED = _UxGT("速度"); // "Velocity" LSTR MSG_VMAX_A = _UxGT("最大进料速率") STR_A; // "Vmax " max_feedrate_mm_s LSTR MSG_VMAX_B = _UxGT("最大进料速率") STR_B; LSTR MSG_VMAX_C = _UxGT("最大进料速率") STR_C; - LSTR MSG_VMAX_I = _UxGT("最大进料速率") STR_I; - LSTR MSG_VMAX_J = _UxGT("最大进料速率") STR_J; - LSTR MSG_VMAX_K = _UxGT("最大进料速率") STR_K; - LSTR MSG_VMAX_E = _UxGT("最大进料速率") STR_E; + LSTR MSG_VMAX_N = _UxGT("最大进料速率@"); + LSTR MSG_VMAX_E = _UxGT("最大进料速率E"); LSTR MSG_VMAX_EN = _UxGT("最大进料速率 *"); LSTR MSG_VMIN = _UxGT("最小进料速率"); // "Vmin" min_feedrate_mm_s LSTR MSG_VTRAV_MIN = _UxGT("最小移动速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move @@ -291,10 +286,8 @@ namespace Language_zh_CN { LSTR MSG_AMAX_A = _UxGT("最大打印加速度") STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves LSTR MSG_AMAX_B = _UxGT("最大打印加速度") STR_B; LSTR MSG_AMAX_C = _UxGT("最大打印加速度") STR_C; - LSTR MSG_AMAX_I = _UxGT("最大打印加速度") STR_I; - LSTR MSG_AMAX_J = _UxGT("最大打印加速度") STR_J; - LSTR MSG_AMAX_K = _UxGT("最大打印加速度") STR_K; - LSTR MSG_AMAX_E = _UxGT("最大打印加速度") STR_E; + LSTR MSG_AMAX_N = _UxGT("最大打印加速度@"); + LSTR MSG_AMAX_E = _UxGT("最大打印加速度E"); LSTR MSG_AMAX_EN = _UxGT("最大打印加速度 *"); LSTR MSG_A_RETRACT = _UxGT("收进加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts LSTR MSG_A_TRAVEL = _UxGT("非打印移动加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves @@ -304,9 +297,7 @@ namespace Language_zh_CN { LSTR MSG_A_STEPS = STR_A _UxGT(" 步数/mm"); // "Asteps/mm" LSTR MSG_B_STEPS = STR_B _UxGT(" 步数/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" 步数/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" 步数/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" 步数/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" 步数/mm"); + LSTR MSG_N_STEPS = _UxGT("@ 步数/mm"); LSTR MSG_E_STEPS = _UxGT("E 步数/mm"); // "Esteps/mm" LSTR MSG_EN_STEPS = _UxGT("* 步数/mm"); LSTR MSG_TEMPERATURE = _UxGT("温度"); // "Temperature" @@ -463,8 +454,6 @@ namespace Language_zh_CN { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校准中心"); // "Calibrate Center" LSTR MSG_DELTA_SETTINGS = _UxGT("⊿设置"); // "Delta Settings" LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("⊿自动校准"); // "Auto Calibration" - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("设置⊿高度"); // "Set Delta Height" - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("探针Z偏移量"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("⊿斜柱"); // "Diag Rod" LSTR MSG_DELTA_HEIGHT = _UxGT("⊿高度"); // "Height" LSTR MSG_DELTA_RADIUS = _UxGT("⊿半径"); // "Radius" @@ -508,13 +497,7 @@ namespace Language_zh_CN { LSTR MSG_INFO_MAX_TEMP = _UxGT("最高温度"); // "Max Temp" LSTR MSG_INFO_PSU = _UxGT("电源供应"); // "Power Supply" LSTR MSG_DRIVE_STRENGTH = _UxGT("驱动力度"); // "Drive Strength" - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" 驱动 %"); // "X Driver %" - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_E = _UxGT("E 驱动 %"); // "E Driver %" + LSTR MSG_DAC_PERCENT_N = _UxGT("@ 驱动 %"); // "E Driver %" LSTR MSG_ERROR_TMC = _UxGT("TMC 连接错误"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("保存驱动设置"); // "DAC EEPROM Write" LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("更换料"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 6c91cc1fec25..b35a486e4f6a 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -65,7 +65,6 @@ namespace Language_zh_TW { LSTR MSG_Z_FADE_HEIGHT = _UxGT("淡出高度"); // "Fade Height" LSTR MSG_SET_HOME_OFFSETS = _UxGT("設置原點偏移"); // "Set home offsets" LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已啟用"); // "Offsets applied" - LSTR MSG_SET_ORIGIN = _UxGT("設置原點"); // "Set origin" #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = _UxGT("預熱 ") PREHEAT_1_LABEL; // "Preheat PREHEAT_1_LABEL" LSTR MSG_PREHEAT_1_H = _UxGT("預熱 ") PREHEAT_1_LABEL " ~"; // "Preheat PREHEAT_1_LABEL" @@ -222,7 +221,7 @@ namespace Language_zh_TW { LSTR MSG_MOVE_E = _UxGT("擠出機"); // "Extruder" LSTR MSG_MOVE_EN = _UxGT("擠出機 *"); // "Extruder *" LSTR MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); // "Hotend too cold" - LSTR MSG_MOVE_N_MM = _UxGT("移動 %s mm"); // "Move 0.025mm" + LSTR MSG_MOVE_N_MM = _UxGT("移動 $ mm"); // "Move 0.025mm" LSTR MSG_MOVE_01MM = _UxGT("移動 0.1 mm"); // "Move 0.1mm" LSTR MSG_MOVE_1MM = _UxGT("移動 1 mm"); // "Move 1mm" LSTR MSG_MOVE_10MM = _UxGT("移動 10 mm"); // "Move 10mm" @@ -255,19 +254,15 @@ namespace Language_zh_TW { LSTR MSG_VA_JERK = _UxGT("軸抖動速率") STR_A; // "Va-jerk" LSTR MSG_VB_JERK = _UxGT("軸抖動速率") STR_B; LSTR MSG_VC_JERK = _UxGT("軸抖動速率") STR_C; - LSTR MSG_VI_JERK = _UxGT("軸抖動速率") STR_I; - LSTR MSG_VJ_JERK = _UxGT("軸抖動速率") STR_J; - LSTR MSG_VK_JERK = _UxGT("軸抖動速率") STR_K; + LSTR MSG_VN_JERK = _UxGT("軸抖動速率@"); LSTR MSG_VE_JERK = _UxGT("擠出機抖動速率"); - LSTR MSG_VELOCITY = _UxGT("速度"); // "Velocity" + LSTR MSG_MAX_SPEED = _UxGT("速度"); // "Velocity" LSTR MSG_VMAX_A = _UxGT("最大進料速率") STR_A; // "Vmax " max_feedrate_mm_s LSTR MSG_VMAX_B = _UxGT("最大進料速率") STR_B; LSTR MSG_VMAX_C = _UxGT("最大進料速率") STR_C; - LSTR MSG_VMAX_I = _UxGT("最大進料速率") STR_I; - LSTR MSG_VMAX_J = _UxGT("最大進料速率") STR_J; - LSTR MSG_VMAX_K = _UxGT("最大進料速率") STR_K; - LSTR MSG_VMAX_E = _UxGT("最大進料速率") STR_E; + LSTR MSG_VMAX_N = _UxGT("最大進料速率@"); + LSTR MSG_VMAX_E = _UxGT("最大進料速率E"); LSTR MSG_VMAX_EN = _UxGT("最大進料速率 *"); // "Vmax " max_feedrate_mm_s LSTR MSG_VMIN = _UxGT("最小進料速率"); // "Vmin" min_feedrate_mm_s LSTR MSG_VTRAV_MIN = _UxGT("最小移動速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move @@ -275,10 +270,8 @@ namespace Language_zh_TW { LSTR MSG_AMAX_A = _UxGT("最大列印加速度") STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves LSTR MSG_AMAX_B = _UxGT("最大列印加速度") STR_B; LSTR MSG_AMAX_C = _UxGT("最大列印加速度") STR_C; - LSTR MSG_AMAX_I = _UxGT("最大列印加速度") STR_I; - LSTR MSG_AMAX_J = _UxGT("最大列印加速度") STR_J; - LSTR MSG_AMAX_K = _UxGT("最大列印加速度") STR_K; - LSTR MSG_AMAX_E = _UxGT("最大列印加速度") STR_E; + LSTR MSG_AMAX_N = _UxGT("最大列印加速度@"); + LSTR MSG_AMAX_E = _UxGT("最大列印加速度E"); LSTR MSG_AMAX_EN = _UxGT("最大列印加速度 *"); // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves LSTR MSG_A_RETRACT = _UxGT("回縮加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts LSTR MSG_A_TRAVEL = _UxGT("非列印移動加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves @@ -286,9 +279,7 @@ namespace Language_zh_TW { LSTR MSG_A_STEPS = STR_A _UxGT(" 軸步數/mm"); // "Asteps/mm" axis_steps_per_mm, axis steps-per-unit G92 LSTR MSG_B_STEPS = STR_B _UxGT(" 軸步數/mm"); LSTR MSG_C_STEPS = STR_C _UxGT(" 軸步數/mm"); - LSTR MSG_I_STEPS = STR_I _UxGT(" 軸步數/mm"); - LSTR MSG_J_STEPS = STR_J _UxGT(" 軸步數/mm"); - LSTR MSG_K_STEPS = STR_K _UxGT(" 軸步數/mm"); + LSTR MSG_N_STEPS = _UxGT("@ 軸步數/mm"); LSTR MSG_E_STEPS = _UxGT("擠出機步數/mm"); // "Esteps/mm" LSTR MSG_EN_STEPS = _UxGT("擠出機~步數/mm"); LSTR MSG_TEMPERATURE = _UxGT("溫度"); // "Temperature" @@ -412,8 +403,6 @@ namespace Language_zh_TW { LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校準中心"); // "Calibrate Center" LSTR MSG_DELTA_SETTINGS = _UxGT("⊿設置"); // "Delta Settings" LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("⊿自動校準"); // "Auto Calibration" - LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("設置⊿高度"); // "Set Delta Height" - LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z偏移"); LSTR MSG_DELTA_DIAG_ROD = _UxGT("⊿斜柱"); // "Diag Rod" LSTR MSG_DELTA_HEIGHT = _UxGT("⊿高度"); // "Height" LSTR MSG_DELTA_RADIUS = _UxGT("⊿半徑"); // "Radius" @@ -455,13 +444,7 @@ namespace Language_zh_TW { LSTR MSG_INFO_MAX_TEMP = _UxGT("最高溫度"); // "Max Temp" LSTR MSG_INFO_PSU = _UxGT("電源供應"); // "Power Supply" LSTR MSG_DRIVE_STRENGTH = _UxGT("驅動力度"); // "Drive Strength" - LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" 驅動 %"); // X Driver % - LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" 驅動 %"); // Y Driver % - LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" 驅動 %"); // Z Driver % - LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" 驅動 %"); // I Driver % - LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" 驅動 %"); // J Driver % - LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" 驅動 %"); // K Driver % - LSTR MSG_DAC_PERCENT_E = _UxGT("E 驅動 %"); //E Driver % + LSTR MSG_DAC_PERCENT_N = _UxGT("@ 驅動 %"); //E Driver % LSTR MSG_ERROR_TMC = _UxGT("TMC連接錯誤"); // "TMC CONNECTION ERROR" LSTR MSG_DAC_EEPROM_WRITE = _UxGT("保存驅動設置"); // "DAC EEPROM Write" LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("更換絲料"); // "FILAMENT CHANGE" diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index 52d30fdfa331..7757379ac9d2 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -32,34 +32,34 @@ #include "lcdprint.h" /** - * lcd_put_u8str_ind_P + * lcd_put_u8str_P * - * Print a string with an index substituted within it: + * Print a string with optional substitutions: * - * $ displays the clipped C-string given by the inStr argument + * $ displays the clipped string given by fstr or cstr * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder */ -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*/) { +lcd_uint_t lcd_put_u8str_P(PGM_P const ptpl, const int8_t ind, const char *cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { const uint8_t prop = USE_WIDE_GLYPH ? 2 : 1; - uint8_t *p = (uint8_t*)pstr; + const uint8_t *p = (uint8_t*)ptpl; int8_t n = maxlen; while (n > 0) { - wchar_t ch; - p = get_utf8_value_cb(p, read_byte_rom, &ch); - if (!ch) break; - if (ch == '=' || ch == '~' || ch == '*') { + lchar_t wc; + p = get_utf8_value_cb(p, read_byte_rom, wc); + if (!wc) break; + if (wc == '=' || wc == '~' || wc == '*') { if (ind >= 0) { - if (ch == '*') { lcd_put_wchar('E'); n--; } + if (wc == '*') { lcd_put_lchar('E'); n--; } if (n) { - int8_t inum = ind + ((ch == '=') ? 0 : LCD_FIRST_TOOL); + int8_t inum = ind + ((wc == '=') ? 0 : LCD_FIRST_TOOL); if (inum >= 10) { - lcd_put_wchar('0' + (inum / 10)); n--; + lcd_put_lchar('0' + (inum / 10)); n--; inum %= 10; } - if (n) { lcd_put_wchar('0' + inum); n--; } + if (n) { lcd_put_lchar('0' + inum); n--; } } } else { @@ -71,16 +71,19 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i break; } } - else if (ch == '$' && inStr) { - n -= lcd_put_u8str_max_P(inStr, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); + else if (wc == '$' && fstr) { + n -= lcd_put_u8str_max_P(FTOP(fstr), n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); } - else if (ch == '@') { - lcd_put_wchar(AXIS_CHAR(ind)); + else if (wc == '$' && cstr) { + n -= lcd_put_u8str_max(cstr, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); + } + else if (wc == '@') { + lcd_put_lchar(AXIS_CHAR(ind)); n--; } else { - lcd_put_wchar(ch); - n -= ch > 255 ? prop : 1; + lcd_put_lchar(wc); + n -= wc > 255 ? prop : 1; } } return n; @@ -90,14 +93,14 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i 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; + const 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; + lchar_t wc; + p = get_utf8_value_cb(p, read_byte_rom, wc); + if (!wc) break; + n += (wc > 255) ? prop : 1; } while (1); return n * MENU_FONT_WIDTH; diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index d716d035caf6..bcf85cb69396 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -130,83 +130,167 @@ int lcd_glyph_height(); -int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length); +/** + * @brief Draw a UTF-8 character + * + * @param utf8_str : the UTF-8 character + * @param max_length : the output width limit (in pixels on GLCD) + * + * @return the output width (in pixels on GLCD) + */ +int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length); /** - * @brief Draw a UTF-8 string + * @brief Draw a SRAM UTF-8 string * * @param utf8_str : the UTF-8 string - * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) - * - * @return the pixel width + * @param max_length : the output width limit (in pixels on GLCD) * - * Draw a UTF-8 string + * @return the output width (in pixels on GLCD) */ -int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length); +int lcd_put_u8str_max(const char *utf8_str, const pixel_len_t max_length); /** - * Set the print baseline position + * Change the print cursor position */ void lcd_moveto(const lcd_uint_t col, const lcd_uint_t row); /** * @brief Draw a ROM UTF-8 string * - * @param utf8_pstr : the ROM UTF-8 string - * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) + * @param pstr : the ROM UTF-8 string + * @param max_length : the output width limit (in pixels on GLCD) * - * @return the pixel width - * - * Draw a ROM UTF-8 string + * @return the output width (in pixels on GLCD) */ -int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length); -inline int lcd_put_u8str_max_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P utf8_pstr, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P pstr, const pixel_len_t max_length); +inline int lcd_put_u8str_max_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P pstr, const pixel_len_t max_length) { lcd_moveto(col, row); - return lcd_put_u8str_max_P(utf8_pstr, max_length); + return lcd_put_u8str_max_P(pstr, max_length); } -inline int lcd_put_u8str_max(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const utf8_fstr, pixel_len_t max_length) { - return lcd_put_u8str_max_P(col, row, FTOP(utf8_fstr), max_length); +inline int lcd_put_u8str_max(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const fstr, const pixel_len_t max_length) { + return lcd_put_u8str_max_P(col, row, FTOP(fstr), max_length); } +/** + * @brief Draw an integer, left-justified + * + * @param i : the integer + */ void lcd_put_int(const int i); inline void lcd_put_int(const lcd_uint_t col, const lcd_uint_t row, const int i) { lcd_moveto(col, row); lcd_put_int(i); } +/** + * @brief Draw a ROM UTF-8 string + * + * @param i : the integer + */ inline int lcd_put_u8str_P(PGM_P const pstr) { return lcd_put_u8str_max_P(pstr, PIXEL_LEN_NOLIMIT); } inline int lcd_put_u8str_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P const pstr) { lcd_moveto(col, row); return lcd_put_u8str_P(pstr); } +/** + * @brief Draw a ROM UTF-8 F-string + * + * @param fstr The F-string pointer + * @return the output width (in pixels on GLCD) + */ inline int lcd_put_u8str(FSTR_P const fstr) { return lcd_put_u8str_P(FTOP(fstr)); } inline int lcd_put_u8str(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const fstr) { return lcd_put_u8str_P(col, row, FTOP(fstr)); } -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); -inline lcd_uint_t lcd_put_u8str_ind_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P const pstr, const int8_t ind, PGM_P const inStr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { +/** + * @brief Draw a string with optional substitution + * @details Print a string with optional substitutions: + * $ displays the clipped string given by fstr or cstr + * = displays '0'....'10' for indexes 0 - 10 + * ~ displays '1'....'11' for indexes 0 - 10 + * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder + * + * @param ptpl A ROM string (template) + * @param ind An index value to use for = ~ * substitution + * @param cstr An SRAM C-string to use for $ substitution + * @param fstr A ROM F-string to use for $ substitution + * @param maxlen The maximum size of the string (in pixels on GLCD) + * @return the output width (in pixels on GLCD) + */ +lcd_uint_t lcd_put_u8str_P(PGM_P const ptpl, const int8_t ind, const char *cstr=nullptr, FSTR_P const fstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH); +inline lcd_uint_t lcd_put_u8str_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P const ptpl, const int8_t ind, const char *cstr=nullptr, FSTR_P const fstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { lcd_moveto(col, row); - return lcd_put_u8str_ind_P(pstr, ind, inStr, maxlen); + return lcd_put_u8str_P(ptpl, ind, cstr, fstr, maxlen); } -inline lcd_uint_t lcd_put_u8str_ind(FSTR_P const fstr, const int8_t ind, FSTR_P const inFstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { - return lcd_put_u8str_ind_P(FTOP(fstr), ind, FTOP(inFstr), maxlen); +/** + * @brief Draw a ROM UTF-8 F-string with optional substitution + * @details (See above) + * + * @param ftpl A ROM F-string (template) + * @param ind An index value to use for = ~ * substitution + * @param cstr An SRAM C-string to use for $ substitution + * @param fstr A ROM F-string to use for $ substitution + * @param maxlen The maximum size of the string (in pixels on GLCD) + * @return the output width (in pixels on GLCD) + */ +inline lcd_uint_t lcd_put_u8str(FSTR_P const ftpl, const int8_t ind, const char *cstr=nullptr, FSTR_P const fstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { + return lcd_put_u8str_P(FTOP(ftpl), ind, cstr, fstr, maxlen); } -inline lcd_uint_t lcd_put_u8str_ind(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const fstr, const int8_t ind, FSTR_P const inFstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { - return lcd_put_u8str_ind_P(col, row, FTOP(fstr), ind, FTOP(inFstr), maxlen); +/** + * @param col + * @param row + */ +inline lcd_uint_t lcd_put_u8str(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const ftpl, const int8_t ind, const char *cstr=nullptr, FSTR_P const fstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { + return lcd_put_u8str_P(col, row, FTOP(ftpl), ind, cstr, fstr, maxlen); } +/** + * @brief Draw a SRAM string with no width limit + * + * @param str The UTF-8 string + * @return the output width (in pixels on GLCD) + */ inline int lcd_put_u8str(const char * const str) { return lcd_put_u8str_max(str, PIXEL_LEN_NOLIMIT); } +/** + * @param col + * @param row + */ inline int lcd_put_u8str(const lcd_uint_t col, const lcd_uint_t row, const char * const str) { lcd_moveto(col, row); return lcd_put_u8str(str); } -inline int lcd_put_wchar(const wchar_t c) { return lcd_put_wchar_max(c, PIXEL_LEN_NOLIMIT); } -inline int lcd_put_wchar(const lcd_uint_t col, const lcd_uint_t row, const wchar_t c) { +/** + * @brief Draw a UTF-8 character with no width limit + * + * @param c The lchar to draw + * @return the output width (in pixels on GLCD) + */ +inline int lcd_put_lchar(const lchar_t &c) { return lcd_put_lchar_max(c, PIXEL_LEN_NOLIMIT); } +/** + * @param col + * @param row + */ +inline int lcd_put_lchar(const lcd_uint_t col, const lcd_uint_t row, const lchar_t &c) { lcd_moveto(col, row); - return lcd_put_wchar(c); + return lcd_put_lchar(c); } +/** + * @brief Calculate the width of a ROM UTF-8 string (in pixels on GLCD) + * + * @param pstr The ROM-based UTF-8 string + * @return the string width (in pixels on GLCD) + */ int calculateWidth(PGM_P const pstr); +/** + * @brief Calculate the width of a ROM UTF-8 string (in pixels on GLCD) + * + * @param pstr The ROM-based UTF-8 string + * @return the string width (in pixels on GLCD) + */ +inline int calculateWidth(FSTR_P const fstr) { return calculateWidth(FTOP(fstr)); } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index d2af634896da..7707cbb05201 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -49,8 +49,6 @@ MarlinUI ui; #include "e3v2/creality/dwin.h" #elif ENABLED(DWIN_LCD_PROUI) #include "e3v2/proui/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "e3v2/jyersui/dwin.h" #endif #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL @@ -118,19 +116,18 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #endif #if ENABLED(SOUND_MENU_ITEM) - bool MarlinUI::buzzer_enabled = true; + bool MarlinUI::sound_on = ENABLED(SOUND_ON_DEFAULT); #endif -#if EITHER(PCA9632_BUZZER, USE_BEEPER) - #include "../libs/buzzer.h" // for BUZZ() macro +#if EITHER(PCA9632_BUZZER, HAS_BEEPER) #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 (!sound_on) return; #if ENABLED(PCA9632_BUZZER) PCA9632_buzz(duration, freq); - #elif USE_BEEPER + #elif HAS_BEEPER buzzer.tone(duration, freq); #endif } @@ -141,12 +138,12 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; preheat_t MarlinUI::material_preset[PREHEAT_COUNT]; // Initialized by settings.load() - PGM_P MarlinUI::get_preheat_label(const uint8_t m) { + FSTR_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]); + return FPSTR((PGM_P)pgm_read_ptr(&preheat_labels[m])); } void MarlinUI::apply_preheat(const uint8_t m, const uint8_t pmask, const uint8_t e/*=active_extruder*/) { @@ -162,7 +159,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; bool MarlinUI::lcd_clicked; #endif -#if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) +#if HAS_WIRED_LCD bool MarlinUI::get_blink() { static uint8_t blink = 0; @@ -417,26 +414,27 @@ void MarlinUI::init() { SETCURSOR(0, row); // Simulate carriage return }; - uint8_t *p = (uint8_t*)string; - wchar_t ch; + const uint8_t *p = (uint8_t*)string; + lchar_t wc; if (wordwrap) { - uint8_t *wrd = nullptr, c = 0; + const uint8_t *wrd = nullptr; + uint8_t 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 + p = get_utf8_value_cb(p, cb_read_byte, wc); + const bool eol = !wc; // zero ends the string // End or a break between phrases? - if (eol || ch == ' ' || ch == '-' || ch == '+' || ch == '.') { - if (!c && ch == ' ') { if (wrd) wrd++; continue; } // collapse extra spaces + if (eol || wc == ' ' || wc == '-' || wc == '+' || wc == '.') { + if (!c && wc == ' ') { 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 + wrd = get_utf8_value_cb(wrd, cb_read_byte, wc); // get characters again + lcd_put_lchar(wc); // character to the LCD } if (eol) break; // all done! wrd = nullptr; // set up for next word @@ -446,29 +444,29 @@ void MarlinUI::init() { } else { for (;;) { - p = get_utf8_value_cb(p, cb_read_byte, &ch); - if (!ch) break; - lcd_put_wchar(ch); + p = get_utf8_value_cb(p, cb_read_byte, wc); + if (!wc) break; + lcd_put_lchar(wc); 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; + void MarlinUI::draw_select_screen_prompt(FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/) { + const uint8_t plen = utf8_strlen(pref), slen = suff ? utf8_strlen(suff) : 0; uint8_t col = 0, row = 0; if (!string && plen + slen <= LCD_WIDTH) { col = (LCD_WIDTH - plen - slen) / 2; row = LCD_HEIGHT > 3 ? 1 : 0; } if (LCD_HEIGHT >= 8) row = LCD_HEIGHT / 2 - 2; - wrap_string_P(col, row, pref, true); + wrap_string_P(col, row, FTOP(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); + if (suff) wrap_string_P(col, row, FTOP(suff)); } #endif // !HAS_GRAPHICAL_TFT @@ -485,17 +483,14 @@ void MarlinUI::init() { #if HAS_MARLINUI_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(); + case X_AXIS: + TERN_(HAS_Y_AXIS, case Y_AXIS:) + TERN_(HAS_Z_AXIS, case Z_AXIS:) + lcd_move_axis(axis); default: break; } } @@ -694,7 +689,7 @@ void MarlinUI::init() { const millis_t ms = millis(); #endif if (ELAPSED(ms, next_beep)) { - buzz(FEEDRATE_CHANGE_BEEP_DURATION, FEEDRATE_CHANGE_BEEP_FREQUENCY); + BUZZ(FEEDRATE_CHANGE_BEEP_DURATION, FEEDRATE_CHANGE_BEEP_FREQUENCY); next_beep = ms + 500UL; } #endif @@ -748,7 +743,7 @@ void MarlinUI::init() { #if HAS_CHIRP chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, USE_BEEPER) + #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -766,6 +761,7 @@ void MarlinUI::init() { millis_t ManualMove::start_time = 0; float ManualMove::menu_scale = 1; + screenFunc_t ManualMove::screen_ptr; #if IS_KINEMATIC float ManualMove::offset = 0; xyze_pos_t ManualMove::all_axes_destination = { 0 }; @@ -775,6 +771,9 @@ void MarlinUI::init() { int8_t ManualMove::e_index = 0; #endif AxisEnum ManualMove::axis = NO_AXIS_ENUM; + #if ENABLED(MANUAL_E_MOVES_RELATIVE) + float ManualMove::e_origin = 0; + #endif /** * If a manual move has been posted and its time has arrived, and if the planner @@ -791,9 +790,6 @@ void MarlinUI::init() { * 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() { @@ -864,7 +860,7 @@ void MarlinUI::init() { void MarlinUI::external_encoder() { if (external_control && encoderDiff) { - ubl.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing + bedlevel.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing encoderDiff = 0; // Hide encoder events from the screen handler refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. } @@ -1577,7 +1573,6 @@ void MarlinUI::init() { TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); TERN_(DWIN_CREALITY_LCD, DWIN_StatusChanged(status_message)); TERN_(DWIN_LCD_PROUI, DWIN_CheckStatusMessage()); - TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Update_Status(status_message)); } #if ENABLED(STATUS_MESSAGE_SCROLLING) @@ -1646,13 +1641,13 @@ void MarlinUI::init() { void MarlinUI::flow_fault() { LCD_ALERTMESSAGE(MSG_FLOWMETER_FAULT); - TERN_(HAS_BUZZER, buzz(1000, 440)); + BUZZ(1000, 440); TERN_(HAS_MARLINUI_MENU, return_to_status()); } void MarlinUI::pause_print() { #if HAS_MARLINUI_MENU - synchronize(GET_TEXT(MSG_PAUSING)); + synchronize(GET_TEXT_F(MSG_PAUSING)); defer_status_screen(); #endif @@ -1756,7 +1751,7 @@ void MarlinUI::init() { if (old_status < 2) { #if ENABLED(EXTENSIBLE_UI) ExtUI::onMediaRemoved(); - #elif PIN_EXISTS(SD_DETECT) + #elif HAS_SD_DETECT LCD_MESSAGE(MSG_MEDIA_REMOVED); #if HAS_MARLINUI_MENU if (!defer_return_to_status) return_to_status(); @@ -1856,12 +1851,12 @@ void MarlinUI::init() { #if DISABLED(EEPROM_AUTO_INIT) - static inline PGM_P eeprom_err(const uint8_t msgid) { + static inline FSTR_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); + case 0: return GET_TEXT_F(MSG_ERR_EEPROM_CRC); + case 1: return GET_TEXT_F(MSG_ERR_EEPROM_INDEX); + case 2: return GET_TEXT_F(MSG_ERR_EEPROM_VERSION); } } @@ -1869,17 +1864,17 @@ void MarlinUI::init() { #if HAS_MARLINUI_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); + FSTR_P const restore_msg = GET_TEXT_F(MSG_INIT_EEPROM); + char msg[utf8_strlen(restore_msg) + 1]; + strcpy_P(msg, FTOP(restore_msg)); MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_RESET), GET_TEXT(MSG_BUTTON_IGNORE), + GET_TEXT_F(MSG_BUTTON_RESET), GET_TEXT_F(MSG_BUTTON_IGNORE), init_eeprom, return_to_status, - eeprom_err(editable.uint8), msg, PSTR("?") + eeprom_err(editable.uint8), msg, F("?") ); }); #else - set_status(FPSTR(eeprom_err(msgid))); + set_status(eeprom_err(msgid)); #endif } diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index cb2d8f8672f0..82b8d78a022c 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -21,15 +21,12 @@ */ #pragma once +#include "../inc/MarlinConfig.h" #include "../sd/cardreader.h" #include "../module/motion.h" -#include "buttons.h" - -#include "../inc/MarlinConfig.h" +#include "../libs/buzzer.h" -#if HAS_BUZZER - #include "../libs/buzzer.h" -#endif +#include "buttons.h" #if ENABLED(TOUCH_SCREEN_CALIBRATION) #include "tft_io/touch_calibration.h" @@ -90,11 +87,9 @@ typedef bool (*statusResetFunc_t)(); #endif // HAS_MARLINUI_MENU -#endif // HAS_WIRED_LCD - -#if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) -#endif + +#endif // HAS_WIRED_LCD #if HAS_MARLINUI_U8GLIB enum MarlinFont : uint8_t { @@ -140,12 +135,16 @@ typedef bool (*statusResetFunc_t)(); static xyze_pos_t all_axes_destination; #endif public: + static screenFunc_t screen_ptr; static float menu_scale; #if IS_KINEMATIC static float offset; #endif + #if ENABLED(MANUAL_E_MOVES_RELATIVE) + static float e_origin; + #endif template - void set_destination(const T& dest) { + static 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. @@ -156,10 +155,10 @@ typedef bool (*statusResetFunc_t)(); current_position.set(dest); #endif } - float axis_value(const AxisEnum axis) { + static 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) { + static 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]; @@ -169,12 +168,7 @@ typedef bool (*statusResetFunc_t)(); #endif valref += diff; const float pre = valref; - if (min != max) { - if (diff < 0) - NOLESS(valref, rmin); - else - NOMORE(valref, rmax); - } + if (min != max) { if (diff < 0) NOLESS(valref, rmin); else NOMORE(valref, rmax); } return pre != valref; } #if IS_KINEMATIC @@ -192,6 +186,9 @@ typedef bool (*statusResetFunc_t)(); //////////// MarlinUI Singleton //////////// //////////////////////////////////////////// +class MarlinUI; +extern MarlinUI ui; + class MarlinUI { public: @@ -225,9 +222,9 @@ class MarlinUI { #endif #if ENABLED(SOUND_MENU_ITEM) - static bool buzzer_enabled; // Initialized by settings.load() + static bool sound_on; // Initialized by settings.load() #else - static constexpr bool buzzer_enabled = true; + static constexpr bool sound_on = true; #endif #if HAS_BUZZER @@ -235,7 +232,7 @@ class MarlinUI { #endif FORCE_INLINE static void chirp() { - TERN_(HAS_CHIRP, buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); + TERN_(HAS_CHIRP, TERN(HAS_BUZZER, buzz, BUZZ)(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); } #if ENABLED(LCD_HAS_STATUS_INDICATORS) @@ -394,7 +391,7 @@ class MarlinUI { static void poweroff(); #endif - #if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) + #if HAS_WIRED_LCD static bool get_blink(); #endif @@ -502,7 +499,6 @@ class MarlinUI { #else // No LCD static void update() {} - static void return_to_status() {} static void kill_screen(FSTR_P const, FSTR_P const) {} #endif @@ -520,7 +516,7 @@ class MarlinUI { #if HAS_PREHEAT enum PreheatTarget : uint8_t { PT_HOTEND, PT_BED, PT_FAN, PT_CHAMBER, PT_ALL = 0xFF }; static preheat_t material_preset[PREHEAT_COUNT]; - static PGM_P get_preheat_label(const uint8_t m); + static FSTR_P get_preheat_label(const uint8_t m); static void apply_preheat(const uint8_t m, const uint8_t pmask, const uint8_t e=active_extruder); static void preheat_set_fan(const uint8_t m) { TERN_(HAS_FAN, apply_preheat(m, _BV(PT_FAN))); } static void preheat_hotend(const uint8_t m, const uint8_t e=active_extruder) { TERN_(HAS_HOTEND, apply_preheat(m, _BV(PT_HOTEND))); } @@ -553,13 +549,14 @@ class MarlinUI { // Manual Movement static ManualMove manual_move; + static bool can_show_slider() { return !external_control && currentScreen != manual_move.screen_ptr; } // 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 void synchronize(FSTR_P const msg=nullptr); static screenFunc_t currentScreen; static bool screen_changed; @@ -605,10 +602,12 @@ class MarlinUI { 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); + static void draw_select_screen_prompt(FSTR_P const pref, const char * const string=nullptr, FSTR_P const suff=nullptr); #else + static void return_to_status() {} + static constexpr bool on_status_screen() { return true; } #if HAS_WIRED_LCD @@ -629,7 +628,7 @@ class MarlinUI { static bool use_click() { return false; } #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else static void _pause_show_message() {} @@ -786,8 +785,6 @@ class MarlinUI { #endif }; -extern MarlinUI ui; - #define LCD_MESSAGE_F(S) ui.set_status(F(S)) #define LCD_MESSAGE(M) ui.set_status(GET_TEXT_F(M)) #define LCD_ALERTMESSAGE_F(S) ui.set_alert_status(F(S)) diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index bcdff450bd4c..a1e2beaf72d0 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -47,7 +47,7 @@ ///////////// Global Variables ///////////// //////////////////////////////////////////// -#if HAS_LEVELING && ANY(LEVEL_BED_CORNERS, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) +#if HAS_LEVELING && ANY(LCD_BED_TRAMMING, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) bool leveling_was_active; // = false #endif #if ANY(PROBE_MANUALLY, MESH_BED_LEVELING, X_AXIS_TWIST_COMPENSATION) @@ -68,12 +68,13 @@ typedef struct { menuPosition screen_history[6]; uint8_t screen_history_depth = 0; -int8_t MenuItemBase::itemIndex; // Index number for draw and action -PGM_P MenuItemBase::itemString; // A PSTR for substitution -chimera_t editable; // Value Editing +int8_t MenuItemBase::itemIndex; // Index number for draw and action +FSTR_P MenuItemBase::itemStringF; // A string for substitution +const char *MenuItemBase::itemStringC; +chimera_t editable; // Value Editing // Menu Edit Items -PGM_P MenuEditItemBase::editLabel; +FSTR_P MenuEditItemBase::editLabel; void* MenuEditItemBase::editValue; int32_t MenuEditItemBase::minEditValue, MenuEditItemBase::maxEditValue; @@ -134,7 +135,7 @@ void MenuEditItemBase::edit_screen(strfunc_t strfunc, loadfunc_t loadfunc) { // Going to an edit screen sets up some persistent values first void MenuEditItemBase::goto_edit_screen( - PGM_P const el, // Edit label + FSTR_P const el, // Edit label void * const ev, // Edit value pointer const int32_t minv, // Encoder minimum const int32_t maxv, // Encoder maximum @@ -163,10 +164,6 @@ void MenuEditItemBase::goto_edit_screen( #include "../../MarlinCore.h" -bool printer_busy() { - return planner.movesplanned() || printingIsActive(); -} - /** * General function to go directly to a screen */ @@ -207,14 +204,14 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co if (on_status_screen()) { defer_status_screen(false); clear_menu_history(); - TERN_(AUTO_BED_LEVELING_UBL, ubl.lcd_map_control = false); + TERN_(AUTO_BED_LEVELING_UBL, bedlevel.lcd_map_control = false); } clear_lcd(); // Re-initialize custom characters that may be re-used #if HAS_MARLINUI_HD44780 - if (TERN1(AUTO_BED_LEVELING_UBL, !ubl.lcd_map_control)) + if (TERN1(AUTO_BED_LEVELING_UBL, !bedlevel.lcd_map_control)) set_custom_characters(on_status_screen() ? CHARSET_INFO : CHARSET_MENU); #endif @@ -236,8 +233,8 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co // Display a "synchronize" screen with a custom message until // all moves are finished. Go back to calling screen when done. // -void MarlinUI::synchronize(PGM_P const msg/*=nullptr*/) { - static PGM_P sync_message = msg ?: GET_TEXT(MSG_MOVING); +void MarlinUI::synchronize(FSTR_P const fmsg/*=nullptr*/) { + static FSTR_P sync_message = fmsg ?: GET_TEXT_F(MSG_MOVING); push_current_screen(); goto_screen([]{ if (should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, sync_message); @@ -323,12 +320,12 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { } if (ui.should_draw()) { if (do_probe) { - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_ZPROBE_ZOFFSET), BABYSTEP_TO_STR(probe.offset.z)); + MenuEditItemBase::draw_edit_screen(GET_TEXT_F(MSG_ZPROBE_ZOFFSET), BABYSTEP_TO_STR(probe.offset.z)); TERN_(BABYSTEP_ZPROBE_GFX_OVERLAY, ui.zoffset_overlay(probe.offset.z)); } else { #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_HOTEND_OFFSET_Z), ftostr54sign(hotend_offset[active_extruder].z)); + MenuEditItemBase::draw_edit_screen(GET_TEXT_F(MSG_HOTEND_OFFSET_Z), ftostr54sign(hotend_offset[active_extruder].z)); #endif } } @@ -339,7 +336,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { void _lcd_draw_homing() { if (ui.should_draw()) { constexpr uint8_t line = (LCD_HEIGHT - 1) / 2; - MenuItem_static::draw(line, GET_TEXT(MSG_LEVEL_BED_HOMING)); + MenuItem_static::draw(line, GET_TEXT_F(MSG_LEVEL_BED_HOMING)); } } @@ -361,9 +358,9 @@ bool MarlinUI::update_selection() { } void MenuItem_confirm::select_screen( - PGM_P const yes, PGM_P const no, + FSTR_P const yes, FSTR_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, - PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/ + FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/ ) { ui.defer_status_screen(); const bool ui_selection = !yes ? false : !no || ui.update_selection(), diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index b111236d69cd..6f5a9efb1516 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -30,7 +30,6 @@ extern int8_t encoderLine, encoderTopLine, screen_items; void scroll_screen(const uint8_t limit, const bool is_menu); -bool printer_busy(); typedef void (*selectFunc_t)(); @@ -54,73 +53,79 @@ class MenuItemBase { // Index to interject in the item label and/or for use by its action. static int8_t itemIndex; - // An optional pointer for use in display or by the action - static PGM_P itemString; + // Optional pointers for use in display or by the action + static FSTR_P itemStringF; + static const char* itemStringC; - // Store the index of the item ahead of use by indexed items - FORCE_INLINE static void init(const int8_t ind=0, PGM_P const pstr=nullptr) { itemIndex = ind; itemString = pstr; } + // Store an index and string for later substitution + FORCE_INLINE static void init(const int8_t ind=0, FSTR_P const fstr=nullptr) { itemIndex = ind; itemStringF = fstr; itemStringC = nullptr; } + FORCE_INLINE static void init(const int8_t ind, const char * const cstr) { itemIndex = ind; itemStringC = cstr; itemStringF = nullptr; } // Implementation-specific: // Draw an item either selected (pre_char) or not (space) with post_char - // Menus may set up itemIndex, itemString and pass them to string-building or string-emitting functions - static void _draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char); + // Menus may set up itemIndex, itemStringC/F and pass them to string-building or string-emitting functions + static void _draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char pre_char, const char post_char); // Draw an item either selected ('>') or not (space) with post_char - FORCE_INLINE static void _draw(const bool sel, const uint8_t row, PGM_P const pstr, const char post_char) { - _draw(sel, row, pstr, '>', post_char); + FORCE_INLINE static void _draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char post_char) { + _draw(sel, row, fstr, '>', post_char); } }; // STATIC_ITEM(LABEL,...) class MenuItem_static : public MenuItemBase { public: - static void draw(const uint8_t row, PGM_P const pstr, const uint8_t style=SS_DEFAULT, const char * const vstr=nullptr); + static void draw(const uint8_t row, FSTR_P const fstr, const uint8_t style=SS_DEFAULT, const char * const vstr=nullptr); }; // BACK_ITEM(LABEL) class MenuItem_back : public MenuItemBase { public: - FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr) { - _draw(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr) { + _draw(sel, row, fstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]); } // Back Item action goes back one step in history - FORCE_INLINE static void action(PGM_P const=nullptr) { ui.go_back(); } + FORCE_INLINE static void action(FSTR_P const=nullptr) { ui.go_back(); } }; // CONFIRM_ITEM(LABEL,Y,N,FY,FN,...), // YESNO_ITEM(LABEL,FY,FN,...) class MenuItem_confirm : public MenuItemBase { public: - 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]); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const ftpl, ...) { + _draw(sel, row, ftpl, '>', LCD_STR_ARROW_RIGHT[0]); } // Implemented for HD44780 and DOGM // Draw the prompt, buttons, and state static void draw_select_screen( - PGM_P const yes, // Right option label - PGM_P const no, // Left option label + FSTR_P const yes, // Right option label + FSTR_P const no, // Left option label const bool yesno, // Is "yes" selected? - PGM_P const pref, // Prompt prefix + FSTR_P const pref, // Prompt prefix const char * const string, // Prompt runtime string - PGM_P const suff // Prompt suffix + FSTR_P const suff // Prompt suffix ); static void select_screen( - PGM_P const yes, PGM_P const no, + FSTR_P const yes, FSTR_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, - PGM_P const pref, const char * const string=nullptr, PGM_P const suff=nullptr + FSTR_P const pref, const char * const string=nullptr, FSTR_P const suff=nullptr ); static void select_screen( - PGM_P const yes, PGM_P const no, + FSTR_P const yes, FSTR_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, - PGM_P const pref, FSTR_P const string, PGM_P const suff=nullptr + FSTR_P const pref, FSTR_P const fstr, FSTR_P const suff=nullptr ) { - char str[strlen_P(FTOP(string)) + 1]; - strcpy_P(str, FTOP(string)); - select_screen(yes, no, yesFunc, noFunc, pref, str, suff); + #ifdef __AVR__ + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); + select_screen(yes, no, yesFunc, noFunc, pref, str, suff); + #else + select_screen(yes, no, yesFunc, noFunc, pref, FTOP(fstr), suff); + #endif } // Shortcut for prompt with "NO"/ "YES" labels - FORCE_INLINE static void confirm_screen(selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string=nullptr, PGM_P const suff=nullptr) { - select_screen(GET_TEXT(MSG_YES), GET_TEXT(MSG_NO), yesFunc, noFunc, pref, string, suff); + FORCE_INLINE static void confirm_screen(selectFunc_t yesFunc, selectFunc_t noFunc, FSTR_P const pref, const char * const string=nullptr, FSTR_P const suff=nullptr) { + select_screen(GET_TEXT_F(MSG_YES), GET_TEXT_F(MSG_NO), yesFunc, noFunc, pref, string, suff); } }; @@ -149,7 +154,7 @@ class MenuEditItemBase : public MenuItemBase { // The action() method acts like the instantiator. The entire lifespan // of a menu item is within its declaration, so all these values decompose // into behavior and unused items get optimized out. - static PGM_P editLabel; + static FSTR_P editLabel; static void *editValue; static int32_t minEditValue, maxEditValue; // Encoder value range static screenFunc_t callbackFunc; @@ -158,7 +163,7 @@ class MenuEditItemBase : public MenuItemBase { typedef const char* (*strfunc_t)(const int32_t); typedef void (*loadfunc_t)(void *, const int32_t); static void goto_edit_screen( - PGM_P const el, // Edit label + FSTR_P const el, // Edit label void * const ev, // Edit value pointer const int32_t minv, // Encoder minimum const int32_t maxv, // Encoder maximum @@ -171,11 +176,15 @@ class MenuEditItemBase : public MenuItemBase { public: // Implementation-specific: // 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, FSTR_P const ftpl, const char * const inStr, const bool pgm=false); + + static void draw(const bool sel, const uint8_t row, FSTR_P const ftpl, FSTR_P const fstr) { + draw(sel, row, ftpl, FTOP(fstr), true); + } // Implementation-specific: // 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(FSTR_P const fstr, const char * const value); // This method is for the current menu item static void draw_edit_screen(const char * const value) { draw_edit_screen(editLabel, value); } @@ -186,7 +195,7 @@ class MenuEditItemBase : public MenuItemBase { class MenuItem_sdbase { public: // Implemented for HD44780 and DOGM - static void draw(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard, const bool isDir); + static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, CardReader &theCard, const bool isDir); }; #endif @@ -205,10 +214,11 @@ void menu_move(); //////// Menu Item Helper Functions //////// //////////////////////////////////////////// +void lcd_move_axis(const AxisEnum); void lcd_move_z(); void _lcd_draw_homing(); -#define HAS_LINE_TO_Z ANY(DELTA, PROBE_MANUALLY, MESH_BED_LEVELING, LEVEL_BED_CORNERS) +#define HAS_LINE_TO_Z ANY(DELTA, PROBE_MANUALLY, MESH_BED_LEVELING, LCD_BED_TRAMMING) #if HAS_LINE_TO_Z void line_to_z(const_float_t z); @@ -255,7 +265,7 @@ inline void clear_menu_history() { screen_history_depth = 0; } #define STICKY_SCREEN(S) []{ ui.defer_status_screen(); ui.goto_screen(S); } -#if HAS_LEVELING && ANY(LEVEL_BED_CORNERS, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) +#if HAS_LEVELING && ANY(LCD_BED_TRAMMING, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) extern bool leveling_was_active; #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 214ff133b2b8..f9f4116bc3a0 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -29,6 +29,7 @@ #if HAS_MARLINUI_MENU #include "menu_item.h" +#include "../../MarlinCore.h" #include "../../module/planner.h" #if DISABLED(NO_VOLUMETRICS) @@ -67,8 +68,10 @@ void menu_backlash(); 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); }) - LOGICAL_AXIS_CODE(EDIT_DAC_PERCENT(E), EDIT_DAC_PERCENT(A), EDIT_DAC_PERCENT(B), EDIT_DAC_PERCENT(C), EDIT_DAC_PERCENT(I), EDIT_DAC_PERCENT(J), EDIT_DAC_PERCENT(K), EDIT_DAC_PERCENT(U), EDIT_DAC_PERCENT(V), EDIT_DAC_PERCENT(W)); + + LOOP_LOGICAL_AXES(a) + EDIT_ITEM_N(uint8, a, MSG_DAC_PERCENT_N, &driverPercent[a], 0, 100, []{ stepper_dac.set_current_percents(driverPercent); }); + ACTION_ITEM(MSG_DAC_EEPROM_WRITE, stepper_dac.commit_eeprom); END_MENU(); } @@ -82,7 +85,7 @@ void menu_backlash(); void menu_pwm() { START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); - #define EDIT_CURRENT_PWM(LABEL,I) EDIT_ITEM_P(long5, PSTR(LABEL), &stepper.motor_current_setting[I], 100, 2000, stepper.refresh_motor_power) + #define EDIT_CURRENT_PWM(LABEL,I) EDIT_ITEM_F(long5, F(LABEL), &stepper.motor_current_setting[I], 100, 2000, stepper.refresh_motor_power) #if ANY_PIN(MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y) EDIT_CURRENT_PWM(STR_A STR_B, 0); #endif @@ -414,7 +417,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_FR_EDITING) DEFAULT_MAX_FEEDRATE #else - LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999, 9999, 9999, 9999, 9999, 9999, 9999) + LOGICAL_AXIS_ARRAY_1(9999) #endif ; #if ENABLED(LIMITED_MAX_FR_EDITING) && !defined(MAX_FEEDRATE_EDIT_VALUES) @@ -426,11 +429,11 @@ void menu_backlash(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); - #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)]) - NUM_AXIS_CODE(EDIT_VMAX(A), EDIT_VMAX(B), EDIT_VMAX(C), EDIT_VMAX(I), EDIT_VMAX(J), EDIT_VMAX(K), EDIT_VMAX(U), EDIT_VMAX(V), EDIT_VMAX(W)); + LOOP_NUM_AXES(a) + EDIT_ITEM_FAST_N(float5, a, MSG_VMAX_N, &planner.settings.max_feedrate_mm_s[a], 1, max_fr_edit_scaled[a]); #if E_STEPPERS - EDIT_ITEM_FAST(float5, MSG_VMAX_E, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e); + EDIT_ITEM_FAST_N(float5, E_AXIS, MSG_VMAX_N, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e); #endif #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(n, E_STEPPERS) @@ -457,7 +460,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_ACCEL_EDITING) DEFAULT_MAX_ACCELERATION #else - LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000, 99000, 99000, 99000, 99000, 99000, 99000) + LOGICAL_AXIS_ARRAY_1(99000) #endif ; #if ENABLED(LIMITED_MAX_ACCEL_EDITING) && !defined(MAX_ACCEL_EDIT_VALUES) @@ -480,7 +483,7 @@ void menu_backlash(); // 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(); }) + #define EDIT_AMAX(Q,L) EDIT_ITEM_FAST_N(long5_25, _AXIS(Q), MSG_AMAX_N, &planner.settings.max_acceleration_mm_per_s2[_AXIS(Q)], L, max_accel_edit_scaled[_AXIS(Q)], []{ planner.refresh_acceleration_rates(); }) NUM_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), @@ -488,14 +491,14 @@ void menu_backlash(); ); #if ENABLED(DISTINCT_E_FACTORS) - EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)], 100, max_accel_edit_scaled.e, []{ planner.reset_acceleration_rates(); }); + EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)], 100, max_accel_edit_scaled.e, []{ planner.refresh_acceleration_rates(); }); LOOP_L_N(n, E_STEPPERS) 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(); + planner.refresh_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(); }); + EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS], 100, max_accel_edit_scaled.e, []{ planner.refresh_acceleration_rates(); }); #endif #ifdef XY_FREQUENCY_LIMIT @@ -514,40 +517,28 @@ void menu_backlash(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #if HAS_JUNCTION_DEVIATION - #if ENABLED(LIN_ADVANCE) - EDIT_ITEM(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.001f, 0.3f, planner.recalculate_max_e_jerk); - #else - EDIT_ITEM(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.001f, 0.5f); - #endif + EDIT_ITEM(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.001f, TERN(LIN_ADVANCE, 0.3f, 0.5f) + OPTARG(LIN_ADVANCE, planner.recalculate_max_e_jerk) + ); #endif constexpr xyze_float_t max_jerk_edit = #ifdef MAX_JERK_EDIT_VALUES MAX_JERK_EDIT_VALUES #elif ENABLED(LIMITED_JERK_EDITING) - { LOGICAL_AXIS_LIST((DEFAULT_EJERK) * 2, - (DEFAULT_XJERK) * 2, (DEFAULT_YJERK) * 2, (DEFAULT_ZJERK) * 2, - (DEFAULT_IJERK) * 2, (DEFAULT_JJERK) * 2, (DEFAULT_KJERK) * 2, - (DEFAULT_UJERK) * 2, (DEFAULT_VJERK) * 2, (DEFAULT_WJERK) * 2) } + #define _JERK2(N) DEFAULT_##N##JERK * 2 + { MAPLIST(_JERK2, LOGICAL_AXIS_NAMES) } #else - { LOGICAL_AXIS_LIST(990, 990, 990, 990, 990, 990, 990, 990, 990, 990) } + LOGICAL_AXIS_ARRAY_1(990) #endif ; - #define EDIT_JERK(N) EDIT_ITEM_FAST(float3, MSG_V##N##_JERK, &planner.max_jerk[_AXIS(N)], 1, max_jerk_edit[_AXIS(N)]) - #if ENABLED(DELTA) - #define EDIT_JERK_C() EDIT_JERK(C) - #else - #define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c) - #endif - NUM_AXIS_CODE( - EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C(), - EDIT_JERK(I), EDIT_JERK(J), EDIT_JERK(K), - EDIT_JERK(U), EDIT_JERK(V), EDIT_JERK(W) - ); - #if HAS_EXTRUDERS - EDIT_ITEM_FAST(float52sign, MSG_VE_JERK, &planner.max_jerk.e, 0.1f, max_jerk_edit.e); - #endif + LOOP_LOGICAL_AXES(a) { + if (a == C_AXIS || TERN0(HAS_EXTRUDERS, a == E_AXIS)) + EDIT_ITEM_FAST_N(float52sign, a, MSG_VN_JERK, &planner.max_jerk[a], 0.1f, max_jerk_edit[a]); + else + EDIT_ITEM_FAST_N(float3, a, MSG_VN_JERK, &planner.max_jerk[a], 1.0f, max_jerk_edit[a]); + } END_MENU(); } @@ -584,12 +575,8 @@ void menu_advanced_steps_per_mm() { START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); - #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float61, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); }) - NUM_AXIS_CODE( - EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C), - EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K), - EDIT_QSTEPS(U), EDIT_QSTEPS(V), EDIT_QSTEPS(W) - ); + LOOP_NUM_AXES(a) + EDIT_ITEM_FAST_N(float61, a, MSG_N_STEPS, &planner.settings.axis_steps_per_mm[a], 5, 9999, []{ planner.refresh_positioning(); }); #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(n, E_STEPPERS) @@ -601,7 +588,7 @@ void menu_advanced_steps_per_mm() { planner.mm_per_step[E_AXIS_N(e)] = 1.0f / planner.settings.axis_steps_per_mm[E_AXIS_N(e)]; }); #elif E_STEPPERS - EDIT_ITEM_FAST(float61, MSG_E_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS], 5, 9999, []{ planner.refresh_positioning(); }); + EDIT_ITEM_FAST_N(float61, E_AXIS, MSG_N_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS], 5, 9999, []{ planner.refresh_positioning(); }); #endif END_MENU(); @@ -627,7 +614,7 @@ void menu_advanced_settings() { #endif // M203 / M205 - Feedrate items - SUBMENU(MSG_VELOCITY, menu_advanced_velocity); + SUBMENU(MSG_MAX_SPEED, menu_advanced_velocity); // M201 - Acceleration items SUBMENU(MSG_ACCELERATION, menu_advanced_acceleration); @@ -708,7 +695,7 @@ void menu_advanced_settings() { CONFIRM_ITEM(MSG_INIT_EEPROM, MSG_BUTTON_INIT, MSG_BUTTON_CANCEL, ui.init_eeprom, nullptr, - GET_TEXT(MSG_INIT_EEPROM), (const char *)nullptr, PSTR("?") + GET_TEXT_F(MSG_INIT_EEPROM), (const char *)nullptr, F("?") ); #endif diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index 07f3c9d7046b..e71606fc12a9 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -47,7 +47,7 @@ void menu_backlash() { #define EDIT_BACKLASH_DISTANCE(N) do { \ editable.decimal = backlash.get_distance_mm(_AXIS(N)); \ - EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &editable.decimal, 0.0f, 9.9f, []{ backlash.set_distance_mm(_AXIS(N), editable.decimal); }); \ + EDIT_ITEM_FAST_N(float43, _AXIS(N), MSG_BACKLASH_N, &editable.decimal, 0.0f, 9.9f, []{ backlash.set_distance_mm(_AXIS(N), editable.decimal); }); \ } while (0); if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index e3f5c460ed24..c4a63dafc6ac 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, LEVEL_BED_CORNERS) +#if BOTH(HAS_MARLINUI_MENU, LCD_BED_TRAMMING) #include "menu_item.h" #include "../../module/motion.h" @@ -36,21 +36,21 @@ #include "../../feature/bedlevel/bedlevel.h" #endif -#ifndef LEVEL_CORNERS_Z_HOP - #define LEVEL_CORNERS_Z_HOP 4.0 +#ifndef BED_TRAMMING_Z_HOP + #define BED_TRAMMING_Z_HOP 4.0 #endif -#ifndef LEVEL_CORNERS_HEIGHT - #define LEVEL_CORNERS_HEIGHT 0.0 +#ifndef BED_TRAMMING_HEIGHT + #define BED_TRAMMING_HEIGHT 0.0 #endif -#if ENABLED(LEVEL_CORNERS_USE_PROBE) +#if ENABLED(BED_TRAMMING_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 + #ifndef BED_TRAMMING_PROBE_TOLERANCE + #define BED_TRAMMING_PROBE_TOLERANCE 0.2 #endif float last_z; int good_points; @@ -64,32 +64,32 @@ #endif -static_assert(LEVEL_CORNERS_Z_HOP >= 0, "LEVEL_CORNERS_Z_HOP must be >= 0. Please update your configuration."); +static_assert(BED_TRAMMING_Z_HOP >= 0, "BED_TRAMMING_Z_HOP must be >= 0. Please update your configuration."); -#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 +#ifndef BED_TRAMMING_LEVELING_ORDER + #define BED_TRAMMING_LEVELING_ORDER { LF, RF, LB, RB } // Default + //#define BED_TRAMMING_LEVELING_ORDER { LF, LB, RF } // 3 hard-coded points + //#define BED_TRAMMING_LEVELING_ORDER { LF, RF } // 3-Point tramming - Rear + //#define BED_TRAMMING_LEVELING_ORDER { LF, LB } // 3-Point tramming - Right + //#define BED_TRAMMING_LEVELING_ORDER { RF, RB } // 3-Point tramming - Left + //#define BED_TRAMMING_LEVELING_ORDER { LB, RB } // 3-Point tramming - Front #endif #define LF 1 #define RF 2 #define RB 3 #define LB 4 -constexpr int lco[] = LEVEL_CORNERS_LEVELING_ORDER; +constexpr int lco[] = BED_TRAMMING_LEVELING_ORDER; constexpr bool level_corners_3_points = COUNT(lco) == 2; -static_assert(level_corners_3_points || COUNT(lco) == 4, "LEVEL_CORNERS_LEVELING_ORDER must have exactly 2 or 4 corners."); +static_assert(level_corners_3_points || COUNT(lco) == 4, "BED_TRAMMING_LEVELING_ORDER must have exactly 2 or 4 corners."); constexpr int lcodiff = ABS(lco[0] - lco[1]); -static_assert(COUNT(lco) == 4 || lcodiff == 1 || lcodiff == 3, "The first two LEVEL_CORNERS_LEVELING_ORDER corners must be on the same edge."); +static_assert(COUNT(lco) == 4 || lcodiff == 1 || lcodiff == 3, "The first two BED_TRAMMING_LEVELING_ORDER corners must be on the same edge."); constexpr int nr_edge_points = level_corners_3_points ? 3 : 4; -constexpr int 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 int available_points = nr_edge_points + ENABLED(BED_TRAMMING_INCLUDE_CENTER); +constexpr int center_index = TERN(BED_TRAMMING_INCLUDE_CENTER, available_points - 1, -1); +constexpr float inset_lfrb[4] = BED_TRAMMING_INSET_LFRB; 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] }; @@ -120,12 +120,12 @@ static void _lcd_level_bed_corners_get_next_position() { 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) + #if DISABLED(BED_TRAMMING_INCLUDE_CENTER) && ENABLED(BED_TRAMMING_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) + #if ENABLED(BED_TRAMMING_INCLUDE_CENTER) case 3: current_position.set(X_CENTER, Y_CENTER); break; @@ -134,9 +134,9 @@ static void _lcd_level_bed_corners_get_next_position() { } else { // Four-Corner Bed Tramming with optional center - if (TERN0(LEVEL_CENTER_TOO, bed_corner == center_index)) { + if (TERN0(BED_TRAMMING_INCLUDE_CENTER, 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 + TERN_(BED_TRAMMING_USE_PROBE, good_points--); // Decrement to allow one additional probe point } else { current_position = lf; // Left front @@ -152,10 +152,10 @@ static void _lcd_level_bed_corners_get_next_position() { /** * Level corners, starting in the front-left corner. */ -#if ENABLED(LEVEL_CORNERS_USE_PROBE) +#if ENABLED(BED_TRAMMING_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.") + "BED_TRAMMING_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"); @@ -168,7 +168,7 @@ static void _lcd_level_bed_corners_get_next_position() { TERN_(HAS_MARLINUI_U8GLIB, ui.set_font(FONT_MENU)); // Set up the font for extra info - MenuItem_static::draw(0, GET_TEXT(MSG_PROBING_POINT), SS_INVERT); // "Probing Mesh" heading + MenuItem_static::draw(0, GET_TEXT_F(MSG_PROBING_POINT), SS_INVERT); // "Probing Mesh" heading uint8_t cy = TERN(TFT_COLOR_UI, 3, LCD_HEIGHT - 1), y = LCD_ROW_Y(cy); @@ -178,7 +178,7 @@ static void _lcd_level_bed_corners_get_next_position() { lcd_put_u8str(GET_TEXT_F(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_lchar('/'); lcd_put_u8str(GOOD_POINTS_TO_STR(nr_edge_points)); } @@ -197,37 +197,35 @@ static void _lcd_level_bed_corners_get_next_position() { void _lcd_draw_raise() { if (!ui.should_draw()) return; MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_DONE), GET_TEXT(MSG_BUTTON_SKIP) + GET_TEXT_F(MSG_BUTTON_DONE), GET_TEXT_F(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 + , GET_TEXT_F(MSG_BED_TRAMMING_RAISE) ); } void _lcd_draw_level_prompt() { if (!ui.should_draw()) return; MenuItem_confirm::select_screen( - GET_TEXT(TERN(HAS_LEVELING, MSG_BUTTON_LEVEL, MSG_BUTTON_DONE)), - TERN(HAS_LEVELING, GET_TEXT(MSG_BUTTON_BACK), nullptr) + GET_TEXT_F(TERN(HAS_LEVELING, MSG_BUTTON_LEVEL, MSG_BUTTON_DONE)), + TERN(HAS_LEVELING, GET_TEXT_F(MSG_BUTTON_BACK), nullptr) , []{ queue.inject(TERN(HAS_LEVELING, F("G29N"), FPSTR(G28_STR))); ui.return_to_status(); } , TERN(HAS_LEVELING, ui.goto_previous_screen_no_defer, []{}) - , GET_TEXT(MSG_BED_TRAMMING_IN_RANGE) - , (const char*)nullptr, NUL_STR + , GET_TEXT_F(MSG_BED_TRAMMING_IN_RANGE) ); } bool _lcd_level_bed_corners_probe(bool verify=false) { - if (verify) do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); // do clearance if needed + if (verify) do_blocking_move_to_z(current_position.z + BED_TRAMMING_Z_HOP); // do clearance if needed TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action - do_blocking_move_to_z(last_z - LEVEL_CORNERS_PROBE_TOLERANCE, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW)); // Move down to lower tolerance + do_blocking_move_to_z(last_z - BED_TRAMMING_PROBE_TOLERANCE, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW)); // Move down to lower tolerance if (TEST(endstops.trigger_state(), Z_MIN_PROBE)) { // check if probe triggered endstops.hit_on_purpose(); set_current_from_steppers_for_axis(Z_AXIS); sync_plan_position(); TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.stow()); // Stow in LOW SPEED MODE on every trigger // Triggered outside tolerance range? - if (ABS(current_position.z - last_z) > LEVEL_CORNERS_PROBE_TOLERANCE) { + if (ABS(current_position.z - last_z) > BED_TRAMMING_PROBE_TOLERANCE) { last_z = current_position.z; // Above tolerance. Set a new Z for subsequent corners. good_points = 0; // ...and start over } @@ -247,7 +245,7 @@ static void _lcd_level_bed_corners_get_next_position() { probe_triggered = PROBE_TRIGGERED(); if (probe_triggered) { endstops.hit_on_purpose(); - TERN_(LEVEL_CORNERS_AUDIO_FEEDBACK, ui.buzz(200, 600)); + TERN_(BED_TRAMMING_AUDIO_FEEDBACK, BUZZ(200, 600)); } idle(); } @@ -257,8 +255,8 @@ static void _lcd_level_bed_corners_get_next_position() { } void _lcd_test_corners() { - bed_corner = TERN(LEVEL_CENTER_TOO, center_index, 0); - last_z = LEVEL_CORNERS_HEIGHT; + bed_corner = TERN(BED_TRAMMING_INCLUDE_CENTER, center_index, 0); + last_z = BED_TRAMMING_HEIGHT; endstops.enable_z_probe(true); good_points = 0; ui.goto_screen(_lcd_draw_probing); @@ -266,7 +264,7 @@ static void _lcd_level_bed_corners_get_next_position() { ui.refresh(LCDVIEW_REDRAW_NOW); _lcd_draw_probing(); // update screen with # of good points - do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP + TERN0(BLTOUCH, bltouch.z_extra_clearance())); // clearance + do_blocking_move_to_z(current_position.z + BED_TRAMMING_Z_HOP + TERN0(BLTOUCH, bltouch.z_extra_clearance())); // clearance _lcd_level_bed_corners_get_next_position(); // Select next corner coordinates current_position -= probe.offset_xy; // Account for probe offsets @@ -275,7 +273,7 @@ static void _lcd_level_bed_corners_get_next_position() { TERN_(BLTOUCH, if (bltouch.high_speed_mode) bltouch.deploy()); // Deploy in HIGH SPEED MODE if (!_lcd_level_bed_corners_probe()) { // Probe down to tolerance if (_lcd_level_bed_corners_raise()) { // Prompt user to raise bed if needed - #if ENABLED(LEVEL_CORNERS_VERIFY_RAISED) // Verify + #if ENABLED(BED_TRAMMING_VERIFY_RAISED) // Verify while (!_lcd_level_bed_corners_probe(true)) { // Loop while corner verified if (!_lcd_level_bed_corners_raise()) { // Prompt user to raise bed if needed if (corner_probing_done) return; // Done was selected @@ -296,7 +294,7 @@ static void _lcd_level_bed_corners_get_next_position() { #if ENABLED(BLTOUCH) if (bltouch.high_speed_mode) { // In HIGH SPEED MODE do clearance and stow at the very end - do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); + do_blocking_move_to_z(current_position.z + BED_TRAMMING_Z_HOP); bltouch.stow(); } #endif @@ -305,25 +303,25 @@ static void _lcd_level_bed_corners_get_next_position() { ui.set_selection(true); } -#else // !LEVEL_CORNERS_USE_PROBE +#else // !BED_TRAMMING_USE_PROBE static void _lcd_goto_next_corner() { - line_to_z(LEVEL_CORNERS_Z_HOP); + line_to_z(BED_TRAMMING_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); + line_to_z(BED_TRAMMING_HEIGHT); if (++bed_corner >= available_points) bed_corner = 0; } -#endif // !LEVEL_CORNERS_USE_PROBE +#endif // !BED_TRAMMING_USE_PROBE static void _lcd_level_bed_corners_homing() { _lcd_draw_homing(); if (!all_axes_homed()) return; - #if ENABLED(LEVEL_CORNERS_USE_PROBE) + #if ENABLED(BED_TRAMMING_USE_PROBE) _lcd_test_corners(); if (corner_probing_done) ui.goto_previous_screen_no_defer(); TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); @@ -332,15 +330,15 @@ static void _lcd_level_bed_corners_homing() { bed_corner = 0; ui.goto_screen([]{ MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_NEXT), GET_TEXT(MSG_BUTTON_DONE) + GET_TEXT_F(MSG_BUTTON_NEXT), GET_TEXT_F(MSG_BUTTON_DONE) , _lcd_goto_next_corner , []{ - line_to_z(LEVEL_CORNERS_Z_HOP); // Raise Z off the bed when done + line_to_z(BED_TRAMMING_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(); } - , GET_TEXT(TERN(LEVEL_CENTER_TOO, MSG_LEVEL_BED_NEXT_POINT, MSG_NEXT_CORNER)) - , (const char*)nullptr, PSTR("?") + , GET_TEXT_F(TERN(BED_TRAMMING_INCLUDE_CENTER, MSG_LEVEL_BED_NEXT_POINT, MSG_NEXT_CORNER)) + , (const char*)nullptr, F("?") ); }); ui.set_selection(true); @@ -364,4 +362,4 @@ void _lcd_level_bed_corners() { ui.goto_screen(_lcd_level_bed_corners_homing); } -#endif // HAS_MARLINUI_MENU && LEVEL_BED_CORNERS +#endif // HAS_MARLINUI_MENU && LCD_BED_TRAMMING diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index a47e2517aedf..294666e35621 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -71,12 +71,12 @@ #if Z_AFTER_PROBING > 0 && DISABLED(MESH_BED_LEVELING) // Display "Done" screen and wait for moves to complete line_to_z(Z_AFTER_PROBING); - ui.synchronize(GET_TEXT(MSG_LEVEL_BED_DONE)); + ui.synchronize(GET_TEXT_F(MSG_LEVEL_BED_DONE)); #endif ui.goto_previous_screen_no_defer(); ui.completion_feedback(); } - if (ui.should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, GET_TEXT(MSG_LEVEL_BED_DONE)); + if (ui.should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, GET_TEXT_F(MSG_LEVEL_BED_DONE)); ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); } @@ -127,7 +127,7 @@ // if (ui.should_draw()) { const float v = current_position.z; - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_MOVE_Z), ftostr43sign(v + (v < 0 ? -0.0001f : 0.0001f), '+')); + MenuEditItemBase::draw_edit_screen(GET_TEXT_F(MSG_MOVE_Z), ftostr43sign(v + (v < 0 ? -0.0001f : 0.0001f), '+')); } } @@ -138,7 +138,7 @@ if (ui.should_draw()) { char msg[10]; sprintf_P(msg, PSTR("%i / %u"), int(manual_probe_index + 1), total_probe_points); - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_LEVEL_BED_NEXT_POINT), msg); + MenuEditItemBase::draw_edit_screen(GET_TEXT_F(MSG_LEVEL_BED_NEXT_POINT), msg); } ui.refresh(LCDVIEW_CALL_NO_REDRAW); if (!ui.wait_for_move) ui.goto_screen(_lcd_level_bed_get_z); @@ -165,7 +165,7 @@ // void _lcd_level_bed_homing_done() { if (ui.should_draw()) { - MenuItem_static::draw(1, GET_TEXT(MSG_LEVEL_BED_WAITING)); + MenuItem_static::draw(1, GET_TEXT_F(MSG_LEVEL_BED_WAITING)); // Color UI needs a control to detect a touch #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); @@ -214,7 +214,7 @@ 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_FAST(float43, MSG_MESH_EDIT_Z, &Z_VALUES(xind, yind), -(LCD_PROBE_Z_RANGE) * 0.5, (LCD_PROBE_Z_RANGE) * 0.5, refresh_planner); + EDIT_ITEM_FAST(float43, MSG_MESH_EDIT_Z, &bedlevel.z_values[xind][yind], -(LCD_PROBE_Z_RANGE) * 0.5, (LCD_PROBE_Z_RANGE) * 0.5, refresh_planner); END_MENU(); } @@ -230,7 +230,7 @@ * Mesh Z Offset: --- (Req: MESH_BED_LEVELING) * Z Probe Offset: --- (Req: HAS_BED_PROBE, Opt: BABYSTEP_ZPROBE_OFFSET) * Level Bed > - * Level Corners > (if homed) + * Bed Tramming > (if homed) * Load Settings (Req: EEPROM_SETTINGS) * Save Settings (Req: EEPROM_SETTINGS) */ @@ -243,7 +243,7 @@ void menu_bed_leveling() { // Auto Home if not using manual probing #if NONE(PROBE_MANUALLY, MESH_BED_LEVELING) - if (!is_homed) GCODES_ITEM(MSG_AUTO_HOME, G28_STR); + if (!is_homed) GCODES_ITEM(MSG_AUTO_HOME, FPSTR(G28_STR)); #endif // Level Bed @@ -252,7 +252,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("G29N")); + GCODES_ITEM(MSG_LEVEL_BED, is_homed ? F("G29") : F("G29N")); #endif #if ENABLED(MESH_EDIT_MENU) @@ -281,7 +281,7 @@ void menu_bed_leveling() { #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); + EDIT_ITEM(LCD_Z_OFFSET_TYPE, MSG_BED_Z, &bedlevel.z_offset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #endif #if ENABLED(BABYSTEP_ZPROBE_OFFSET) @@ -290,7 +290,7 @@ void menu_bed_leveling() { EDIT_ITEM(LCD_Z_OFFSET_TYPE, MSG_ZPROBE_ZOFFSET, &probe.offset.z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #endif - #if ENABLED(LEVEL_BED_CORNERS) + #if ENABLED(LCD_BED_TRAMMING) SUBMENU(MSG_BED_TRAMMING, _lcd_level_bed_corners); #endif diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp index 8db698d300f2..b2d36bf8c30d 100644 --- a/Marlin/src/lcd/menu/menu_cancelobject.cpp +++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp @@ -48,7 +48,7 @@ static void lcd_cancel_object_confirm() { ui.goto_previous_screen(); }, nullptr, - GET_TEXT(MSG_CANCEL_OBJECT), item_num, PSTR("?") + GET_TEXT_F(MSG_CANCEL_OBJECT), item_num, F("?") ); } diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index d4590a65f902..1f2257a77fe3 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -30,6 +30,8 @@ #include "menu_item.h" +#include "../../MarlinCore.h" + #if HAS_FILAMENT_SENSOR #include "../../feature/runout.h" #endif @@ -76,8 +78,8 @@ void menu_advanced_settings(); bar_percent += (int8_t)ui.encoderPosition; LIMIT(bar_percent, 0, 100); ui.encoderPosition = 0; - MenuItem_static::draw(0, GET_TEXT(MSG_PROGRESS_BAR_TEST), SS_DEFAULT|SS_INVERT); - lcd_put_int((LCD_WIDTH) / 2 - 2, LCD_HEIGHT - 2, bar_percent); lcd_put_wchar('%'); + MenuItem_static::draw(0, GET_TEXT_F(MSG_PROGRESS_BAR_TEST), SS_DEFAULT|SS_INVERT); + lcd_put_int((LCD_WIDTH) / 2 - 2, LCD_HEIGHT - 2, bar_percent); lcd_put_lchar('%'); lcd_moveto(0, LCD_HEIGHT - 1); ui.draw_progress_bar(bar_percent); } @@ -135,7 +137,7 @@ void menu_advanced_settings(); #include "../../gcode/queue.h" void menu_toolchange_migration() { - PGM_P const msg_migrate = GET_TEXT(MSG_TOOL_MIGRATION_SWAP); + FSTR_P const msg_migrate = GET_TEXT_F(MSG_TOOL_MIGRATION_SWAP); START_MENU(); BACK_ITEM(MSG_CONFIGURATION); @@ -147,7 +149,7 @@ void menu_advanced_settings(); // Migrate to a chosen extruder EXTRUDER_LOOP() { if (e != active_extruder) { - ACTION_ITEM_N_P(e, msg_migrate, []{ + ACTION_ITEM_N_F(e, msg_migrate, []{ char cmd[12]; sprintf_P(cmd, PSTR("M217 T%i"), int(MenuItemBase::itemIndex)); queue.inject(cmd); @@ -197,16 +199,16 @@ void menu_advanced_settings(); START_MENU(); BACK_ITEM(MSG_CONFIGURATION); - GCODES_ITEM(MSG_IDEX_MODE_AUTOPARK, PSTR("M605S1\nG28X\nG1X0")); + GCODES_ITEM(MSG_IDEX_MODE_AUTOPARK, F("M605S1\nG28X\nG1X0")); GCODES_ITEM(MSG_IDEX_MODE_DUPLICATE, need_g28 - ? 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") + ? F("M605S1\nT0\nG28\nM605S2\nG28X\nG1X0") // If Y or Z is not homed, do a full G28 first + : F("M605S1\nT0\nM605S2\nG28X\nG1X0") ); GCODES_ITEM(MSG_IDEX_MODE_MIRRORED_COPY, need_g28 - ? 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") + ? F("M605S1\nT0\nG28\nM605S2\nG28X\nG1X0\nM605S3") // If Y or Z is not homed, do a full G28 first + : F("M605S1\nT0\nM605S2\nG28 X\nG1X0\nM605S3") ); - GCODES_ITEM(MSG_IDEX_MODE_FULL_CTRL, PSTR("M605S0\nG28X")); + GCODES_ITEM(MSG_IDEX_MODE_FULL_CTRL, F("M605S0\nG28X")); EDIT_ITEM(float42_52, MSG_IDEX_DUPE_GAP, &duplicate_extruder_x_offset, (X2_MIN_POS) - (X1_MIN_POS), (X_BED_SIZE) - 20); @@ -244,11 +246,11 @@ void menu_advanced_settings(); EDIT_ITEM(bool, MSG_BLTOUCH_SPEED_MODE, &bltouch.high_speed_mode); #endif #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) - CONFIRM_ITEM(MSG_BLTOUCH_5V_MODE, MSG_BLTOUCH_5V_MODE, MSG_BUTTON_CANCEL, bltouch._set_5V_mode, nullptr, GET_TEXT(MSG_BLTOUCH_MODE_CHANGE)); - CONFIRM_ITEM(MSG_BLTOUCH_OD_MODE, MSG_BLTOUCH_OD_MODE, MSG_BUTTON_CANCEL, bltouch._set_OD_mode, nullptr, GET_TEXT(MSG_BLTOUCH_MODE_CHANGE)); + CONFIRM_ITEM(MSG_BLTOUCH_5V_MODE, MSG_BLTOUCH_5V_MODE, MSG_BUTTON_CANCEL, bltouch._set_5V_mode, nullptr, GET_TEXT_F(MSG_BLTOUCH_MODE_CHANGE)); + CONFIRM_ITEM(MSG_BLTOUCH_OD_MODE, MSG_BLTOUCH_OD_MODE, MSG_BUTTON_CANCEL, bltouch._set_OD_mode, nullptr, GET_TEXT_F(MSG_BLTOUCH_MODE_CHANGE)); ACTION_ITEM(MSG_BLTOUCH_MODE_STORE, bltouch._mode_store); - CONFIRM_ITEM(MSG_BLTOUCH_MODE_STORE_5V, MSG_BLTOUCH_MODE_STORE_5V, MSG_BUTTON_CANCEL, bltouch.mode_conv_5V, nullptr, GET_TEXT(MSG_BLTOUCH_MODE_CHANGE)); - CONFIRM_ITEM(MSG_BLTOUCH_MODE_STORE_OD, MSG_BLTOUCH_MODE_STORE_OD, MSG_BUTTON_CANCEL, bltouch.mode_conv_OD, nullptr, GET_TEXT(MSG_BLTOUCH_MODE_CHANGE)); + CONFIRM_ITEM(MSG_BLTOUCH_MODE_STORE_5V, MSG_BLTOUCH_MODE_STORE_5V, MSG_BUTTON_CANCEL, bltouch.mode_conv_5V, nullptr, GET_TEXT_F(MSG_BLTOUCH_MODE_CHANGE)); + CONFIRM_ITEM(MSG_BLTOUCH_MODE_STORE_OD, MSG_BLTOUCH_MODE_STORE_OD, MSG_BUTTON_CANCEL, bltouch.mode_conv_OD, nullptr, GET_TEXT_F(MSG_BLTOUCH_MODE_CHANGE)); ACTION_ITEM(MSG_BLTOUCH_MODE_ECHO, bltouch_report); #endif END_MENU(); @@ -262,10 +264,10 @@ void menu_advanced_settings(); ui.defer_status_screen(); START_MENU(); BACK_ITEM(MSG_CONFIGURATION); - GCODES_ITEM(MSG_TOUCHMI_INIT, PSTR("M851 Z0\nG28\nG1 F200 Z0")); + GCODES_ITEM(MSG_TOUCHMI_INIT, F("M851 Z0\nG28\nG1 F200 Z0")); SUBMENU(MSG_ZPROBE_ZOFFSET, lcd_babystep_zoffset); - GCODES_ITEM(MSG_TOUCHMI_SAVE, PSTR("M500\nG1 F200 Z10")); - GCODES_ITEM(MSG_TOUCHMI_ZTEST, PSTR("G28\nG1 F200 Z0")); + GCODES_ITEM(MSG_TOUCHMI_SAVE, F("M500\nG1 F200 Z10")); + GCODES_ITEM(MSG_TOUCHMI_ZTEST, F("G28\nG1 F200 Z0")); END_MENU(); } @@ -327,7 +329,7 @@ void menu_advanced_settings(); #define MAXTEMP_ALL _MAX(REPEAT(HOTENDS, _MAXTEMP_ITEM) 0) const uint8_t m = MenuItemBase::itemIndex; START_MENU(); - STATIC_ITEM_P(ui.get_preheat_label(m), SS_DEFAULT|SS_INVERT); + STATIC_ITEM_F(ui.get_preheat_label(m), SS_DEFAULT|SS_INVERT); BACK_ITEM(MSG_CONFIGURATION); #if HAS_FAN editable.uint8 = uint8_t(ui.material_preset[m].fan_speed); @@ -367,13 +369,13 @@ void menu_advanced_settings(); #define _DONE_SCRIPT "" #endif #define GCODE_LAMBDA_CONF(N) []{ _lcd_custom_menus_configuration_gcode(F(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), nullptr, \ - PSTR(CONFIG_MENU_ITEM_##N##_DESC "?") \ - ); \ + #define _CUSTOM_ITEM_CONF(N) ACTION_ITEM_F(F(CONFIG_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_CONF(N)); + #define _CUSTOM_ITEM_CONF_CONFIRM(N) \ + SUBMENU_F(F(CONFIG_MENU_ITEM_##N##_DESC), []{ \ + MenuItem_confirm::confirm_screen( \ + GCODE_LAMBDA_CONF(N), nullptr, \ + F(CONFIG_MENU_ITEM_##N##_DESC "?") \ + ); \ }) #define CUSTOM_ITEM_CONF(N) do{ \ @@ -481,7 +483,7 @@ void menu_configuration() { #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); + SUBMENU_F(F(CUSTOM_MENU_CONFIG_TITLE), custom_menus_configuration); #else SUBMENU(MSG_CUSTOM_COMMANDS, custom_menus_configuration); #endif @@ -570,11 +572,11 @@ void menu_configuration() { // Preheat configurations #if HAS_PREHEAT && DISABLED(SLIM_LCD_MENUS) LOOP_L_N(m, PREHEAT_COUNT) - SUBMENU_N_S(m, ui.get_preheat_label(m), MSG_PREHEAT_M_SETTINGS, _menu_configuration_preheat_settings); + SUBMENU_N_f(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(); }); + EDIT_ITEM(bool, MSG_SOUND, &ui.sound_on, []{ ui.chirp(); }); #endif #if ENABLED(EEPROM_SETTINGS) diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index f491c5b576ee..b86f1012586d 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -41,6 +41,10 @@ #include "../extui/ui_api.h" #endif +#if HAS_PROBE_XY_OFFSET + #include "../../module/probe.h" +#endif + void _man_probe_pt(const xy_pos_t &xy) { if (!ui.wait_for_move) { ui.wait_for_move = true; @@ -88,7 +92,9 @@ void _man_probe_pt(const xy_pos_t &xy) { } void _goto_tower_a(const_float_t a) { - constexpr float dcr = DELTA_PRINTABLE_RADIUS; + float dcr = DELTA_PRINTABLE_RADIUS - PROBING_MARGIN; + TERN_(HAS_PROBE_XY_OFFSET, dcr -= HYPOT(probe.offset_xy.x, probe.offset_xy.y)); + TERN_(HAS_DELTA_SENSORLESS_PROBING, dcr *= sensorless_radius_factor); xy_pos_t tower_vec = { cos(RADIANS(a)), sin(RADIANS(a)) }; _man_probe_pt(tower_vec * dcr); } @@ -107,12 +113,12 @@ 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, 0, _recalc_delta_settings) + #define EDIT_ENDSTOP_ADJ(LABEL,N) EDIT_ITEM_F(float43, F(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); EDIT_ITEM(float52sign, MSG_DELTA_RADIUS, &delta_radius, delta_radius - 5, delta_radius + 5, _recalc_delta_settings); - #define EDIT_ANGLE_TRIM(LABEL,N) EDIT_ITEM_P(float43, PSTR(LABEL), &delta_tower_angle_trim.N, -5, 5, _recalc_delta_settings) + #define EDIT_ANGLE_TRIM(LABEL,N) EDIT_ITEM_F(float43, F(LABEL), &delta_tower_angle_trim.N, -5, 5, _recalc_delta_settings) EDIT_ANGLE_TRIM("Tx", a); EDIT_ANGLE_TRIM("Ty", b); EDIT_ANGLE_TRIM("Tz", c); @@ -129,7 +135,7 @@ void menu_delta_calibrate() { BACK_ITEM(MSG_MAIN); #if ENABLED(DELTA_AUTO_CALIBRATION) - GCODES_ITEM(MSG_DELTA_AUTO_CALIBRATE, PSTR("G33")); + GCODES_ITEM(MSG_DELTA_AUTO_CALIBRATE, F("G33")); #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); ACTION_ITEM(MSG_LOAD_EEPROM, ui.load_settings); diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 9f432c405c4f..5902a2f63f35 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -35,6 +35,9 @@ #if HAS_FILAMENT_SENSOR #include "../../feature/runout.h" #endif +#if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + #include "../../MarlinCore.h" +#endif // // Change Filament > Change/Unload/Load Filament @@ -42,22 +45,22 @@ static PauseMode _change_filament_mode; // = PAUSE_MODE_PAUSE_PRINT static int8_t _change_filament_extruder; // = 0 -inline PGM_P _change_filament_command() { +inline FSTR_P _change_filament_command() { switch (_change_filament_mode) { - case PAUSE_MODE_LOAD_FILAMENT: return PSTR("M701 T%d"); + case PAUSE_MODE_LOAD_FILAMENT: return F("M701 T%d"); case PAUSE_MODE_UNLOAD_FILAMENT: return _change_filament_extruder >= 0 - ? PSTR("M702 T%d") : PSTR("M702 ;%d"); + ? F("M702 T%d") : F("M702 ;%d"); case PAUSE_MODE_CHANGE_FILAMENT: case PAUSE_MODE_PAUSE_PRINT: default: break; } - return PSTR("M600 B0 T%d"); + return F("M600 B0 T%d"); } // Initiate Filament Load/Unload/Change at the specified temperature static void _change_filament_with_temp(const uint16_t celsius) { char cmd[11]; - sprintf_P(cmd, _change_filament_command(), _change_filament_extruder); + sprintf_P(cmd, FTOP(_change_filament_command()), _change_filament_extruder); thermalManager.setTargetHotend(celsius, _change_filament_extruder); queue.inject(cmd); } @@ -74,13 +77,13 @@ static void _change_filament_with_custom() { // Menu to choose the temperature and start Filament Change // -inline PGM_P change_filament_header(const PauseMode mode) { +inline FSTR_P change_filament_header(const PauseMode mode) { switch (mode) { - case PAUSE_MODE_LOAD_FILAMENT: return GET_TEXT(MSG_FILAMENTLOAD); - case PAUSE_MODE_UNLOAD_FILAMENT: return GET_TEXT(MSG_FILAMENTUNLOAD); + case PAUSE_MODE_LOAD_FILAMENT: return GET_TEXT_F(MSG_FILAMENTLOAD); + case PAUSE_MODE_UNLOAD_FILAMENT: return GET_TEXT_F(MSG_FILAMENTUNLOAD); default: break; } - return GET_TEXT(MSG_FILAMENTCHANGE); + return GET_TEXT_F(MSG_FILAMENTCHANGE); } void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { @@ -88,11 +91,11 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { _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); + if (LCD_HEIGHT >= 4) STATIC_ITEM_F(change_filament_header(mode), SS_DEFAULT|SS_INVERT); BACK_ITEM(MSG_BACK); #if HAS_PREHEAT LOOP_L_N(m, PREHEAT_COUNT) - ACTION_ITEM_N_S(m, ui.get_preheat_label(m), MSG_PREHEAT_M, _change_filament_with_preset); + ACTION_ITEM_N_f(m, ui.get_preheat_label(m), MSG_PREHEAT_M, _change_filament_with_preset); #endif EDIT_ITEM_FAST_N(int3, extruder, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[extruder].target, EXTRUDE_MINTEMP, thermalManager.hotend_max_target(extruder), @@ -129,18 +132,18 @@ void menu_change_filament() { // Change filament #if E_STEPPERS == 1 - PGM_P const msg = GET_TEXT(MSG_FILAMENTCHANGE); + FSTR_P const fmsg = GET_TEXT_F(MSG_FILAMENTCHANGE); if (thermalManager.targetTooColdToExtrude(active_extruder)) - SUBMENU_P(msg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); + SUBMENU_F(fmsg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); else - GCODES_ITEM_P(msg, PSTR("M600 B0")); + GCODES_ITEM_F(fmsg, F("M600 B0")); #else - PGM_P const msg = GET_TEXT(MSG_FILAMENTCHANGE_E); + FSTR_P const fmsg = GET_TEXT_F(MSG_FILAMENTCHANGE_E); LOOP_L_N(s, E_STEPPERS) { if (thermalManager.targetTooColdToExtrude(s)) - SUBMENU_N_P(s, msg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, MenuItemBase::itemIndex); }); + SUBMENU_N_F(s, fmsg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, MenuItemBase::itemIndex); }); else { - ACTION_ITEM_N_P(s, msg, []{ + ACTION_ITEM_N_F(s, fmsg, []{ PGM_P const cmdpstr = PSTR("M600 B0 T%i"); char cmd[strlen_P(cmdpstr) + 3 + 1]; sprintf_P(cmd, cmdpstr, int(MenuItemBase::itemIndex)); @@ -154,18 +157,18 @@ void menu_change_filament() { if (!is_busy) { // Load filament #if E_STEPPERS == 1 - PGM_P const msg_load = GET_TEXT(MSG_FILAMENTLOAD); + FSTR_P const msg_load = GET_TEXT_F(MSG_FILAMENTLOAD); if (thermalManager.targetTooColdToExtrude(active_extruder)) - SUBMENU_P(msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, 0); }); + SUBMENU_F(msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, 0); }); else - GCODES_ITEM_P(msg_load, PSTR("M701")); + GCODES_ITEM_F(msg_load, F("M701")); #else - PGM_P const msg_load = GET_TEXT(MSG_FILAMENTLOAD_E); + FSTR_P const msg_load = GET_TEXT_F(MSG_FILAMENTLOAD_E); LOOP_L_N(s, E_STEPPERS) { if (thermalManager.targetTooColdToExtrude(s)) - SUBMENU_N_P(s, msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, MenuItemBase::itemIndex); }); + SUBMENU_N_F(s, msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, MenuItemBase::itemIndex); }); else { - ACTION_ITEM_N_P(s, msg_load, []{ + ACTION_ITEM_N_F(s, msg_load, []{ char cmd[12]; sprintf_P(cmd, PSTR("M701 T%i"), int(MenuItemBase::itemIndex)); queue.inject(cmd); @@ -176,24 +179,24 @@ void menu_change_filament() { // Unload filament #if E_STEPPERS == 1 - PGM_P const msg_unload = GET_TEXT(MSG_FILAMENTUNLOAD); + FSTR_P const msg_unload = GET_TEXT_F(MSG_FILAMENTUNLOAD); if (thermalManager.targetTooColdToExtrude(active_extruder)) - SUBMENU_P(msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, 0); }); + SUBMENU_F(msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, 0); }); else - GCODES_ITEM_P(msg_unload, PSTR("M702")); + GCODES_ITEM_F(msg_unload, F("M702")); #else #if ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) if (too_cold) SUBMENU(MSG_FILAMENTUNLOAD_ALL, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, -1); }); else - GCODES_ITEM(MSG_FILAMENTUNLOAD_ALL, PSTR("M702")); + GCODES_ITEM(MSG_FILAMENTUNLOAD_ALL, F("M702")); #endif - PGM_P const msg_unload = GET_TEXT(MSG_FILAMENTUNLOAD_E); + FSTR_P const msg_unload = GET_TEXT_F(MSG_FILAMENTUNLOAD_E); LOOP_L_N(s, E_STEPPERS) { if (thermalManager.targetTooColdToExtrude(s)) - SUBMENU_N_P(s, msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, MenuItemBase::itemIndex); }); + SUBMENU_N_F(s, msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, MenuItemBase::itemIndex); }); else { - ACTION_ITEM_N_P(s, msg_unload, []{ + ACTION_ITEM_N_F(s, msg_unload, []{ char cmd[12]; sprintf_P(cmd, PSTR("M702 T%i"), int(MenuItemBase::itemIndex)); queue.inject(cmd); @@ -218,21 +221,21 @@ void menu_change_filament() { static uint8_t hotend_status_extruder = 0; -static PGM_P pause_header() { +static FSTR_P pause_header() { switch (pause_mode) { - case PAUSE_MODE_CHANGE_FILAMENT: return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER); - case PAUSE_MODE_LOAD_FILAMENT: return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER_LOAD); - case PAUSE_MODE_UNLOAD_FILAMENT: return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER_UNLOAD); + case PAUSE_MODE_CHANGE_FILAMENT: return GET_TEXT_F(MSG_FILAMENT_CHANGE_HEADER); + case PAUSE_MODE_LOAD_FILAMENT: return GET_TEXT_F(MSG_FILAMENT_CHANGE_HEADER_LOAD); + case PAUSE_MODE_UNLOAD_FILAMENT: return GET_TEXT_F(MSG_FILAMENT_CHANGE_HEADER_UNLOAD); default: break; } - return GET_TEXT(MSG_FILAMENT_CHANGE_HEADER_PAUSE); + return GET_TEXT_F(MSG_FILAMENT_CHANGE_HEADER_PAUSE); } // Portions from STATIC_ITEM... #define HOTEND_STATUS_ITEM() do { \ if (_menuLineNr == _thisItemNr) { \ if (ui.should_draw()) { \ - IF_DISABLED(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_F(MSG_FILAMENT_CHANGE_NOZZLE), SS_INVERT)); \ ui.draw_hotend_status(_lcdLineNr, hotend_status_extruder); \ } \ if (_skipStatic && encoderLine <= _thisItemNr) { \ @@ -268,41 +271,41 @@ void menu_pause_option() { // // ADVANCED_PAUSE_FEATURE message screens // -// Warning: msg must have three null bytes to delimit lines! +// Warning: fmsg must have three null bytes to delimit lines! // -void _lcd_pause_message(PGM_P const msg) { - PGM_P const msg1 = msg; +void _lcd_pause_message(FSTR_P const fmsg) { + PGM_P const msg1 = FTOP(fmsg); PGM_P const msg2 = msg1 + strlen_P(msg1) + 1; PGM_P const msg3 = msg2 + strlen_P(msg2) + 1; const bool has2 = msg2[0], has3 = msg3[0], skip1 = !has2 && (LCD_HEIGHT) >= 5; START_SCREEN(); - STATIC_ITEM_P(pause_header(), SS_DEFAULT|SS_INVERT); // 1: Header + STATIC_ITEM_F(pause_header(), SS_DEFAULT|SS_INVERT); // 1: Header if (skip1) SKIP_ITEM(); // Move a single-line message down - STATIC_ITEM_P(msg1); // 2: Message Line 1 - if (has2) STATIC_ITEM_P(msg2); // 3: Message Line 2 - if (has3 && (LCD_HEIGHT) >= 5) STATIC_ITEM_P(msg3); // 4: Message Line 3 (if LCD has 5 lines) + STATIC_ITEM_F(FPSTR(msg1)); // 2: Message Line 1 + if (has2) STATIC_ITEM_F(FPSTR(msg2)); // 3: Message Line 2 + if (has3 && (LCD_HEIGHT) >= 5) STATIC_ITEM_F(FPSTR(msg3)); // 4: Message Line 3 (if LCD has 5 lines) if (skip1 + 1 + has2 + has3 < (LCD_HEIGHT) - 2) SKIP_ITEM(); // Push Hotend Status down, if needed HOTEND_STATUS_ITEM(); // 5: Hotend Status END_SCREEN(); } -void lcd_pause_parking_message() { _lcd_pause_message(GET_TEXT(MSG_PAUSE_PRINT_PARKING)); } -void lcd_pause_changing_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_INIT)); } -void lcd_pause_unload_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_UNLOAD)); } -void lcd_pause_heating_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); } -void lcd_pause_heat_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_HEAT)); } -void lcd_pause_insert_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_INSERT)); } -void lcd_pause_load_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_LOAD)); } -void lcd_pause_waiting_message() { _lcd_pause_message(GET_TEXT(MSG_ADVANCED_PAUSE_WAITING)); } -void lcd_pause_resume_message() { _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_RESUME)); } +void lcd_pause_parking_message() { _lcd_pause_message(GET_TEXT_F(MSG_PAUSE_PRINT_PARKING)); } +void lcd_pause_changing_message() { _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_INIT)); } +void lcd_pause_unload_message() { _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_UNLOAD)); } +void lcd_pause_heating_message() { _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEATING)); } +void lcd_pause_heat_message() { _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT)); } +void lcd_pause_insert_message() { _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_INSERT)); } +void lcd_pause_load_message() { _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_LOAD)); } +void lcd_pause_waiting_message() { _lcd_pause_message(GET_TEXT_F(MSG_ADVANCED_PAUSE_WAITING)); } +void lcd_pause_resume_message() { _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_RESUME)); } void lcd_pause_purge_message() { #if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE) - _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_CONT_PURGE)); + _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_CONT_PURGE)); #else - _lcd_pause_message(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE)); + _lcd_pause_message(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE)); #endif } diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 3a23cf004884..101861074d95 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -35,7 +35,7 @@ #endif #define VALUE_ITEM(MSG, VALUE, STYL) do{ char msg[21]; strcpy_P(msg, PSTR(": ")); strcpy(msg + 2, VALUE); STATIC_ITEM(MSG, STYL, msg); }while(0) -#define VALUE_ITEM_P(MSG, PVALUE, STYL) do{ char msg[21]; strcpy_P(msg, PSTR(": ")); strcpy_P(msg + 2, PSTR(PVALUE)); STATIC_ITEM(MSG, STYL, msg); }while(0) +#define VALUE_ITEM_F(MSG, PVALUE, STYL) do{ char msg[21]; strcpy_P(msg, PSTR(": ")); strcpy_P(msg + 2, PSTR(PVALUE)); STATIC_ITEM(MSG, STYL, msg); }while(0) #if ENABLED(PRINTCOUNTER) @@ -56,35 +56,35 @@ VALUE_ITEM(MSG_INFO_COMPLETED_PRINTS, i16tostr3left(stats.finishedPrints), SS_LEFT); // Completed : 666 STATIC_ITEM(MSG_INFO_PRINT_TIME, SS_LEFT); // Total print Time: - STATIC_ITEM_P(PSTR("> "), SS_LEFT, duration_t(stats.printTime).toString(buffer)); // > 99y 364d 23h 59m 59s + STATIC_ITEM_F(F("> "), SS_LEFT, duration_t(stats.printTime).toString(buffer)); // > 99y 364d 23h 59m 59s STATIC_ITEM(MSG_INFO_PRINT_LONGEST, SS_LEFT); // Longest job time: - STATIC_ITEM_P(PSTR("> "), SS_LEFT, duration_t(stats.longestPrint).toString(buffer)); // > 99y 364d 23h 59m 59s + STATIC_ITEM_F(F("> "), SS_LEFT, duration_t(stats.longestPrint).toString(buffer)); // > 99y 364d 23h 59m 59s STATIC_ITEM(MSG_INFO_PRINT_FILAMENT, SS_LEFT); // Extruded total: sprintf_P(buffer, PSTR("%ld.%im") , long(stats.filamentUsed / 1000) , int16_t(stats.filamentUsed / 100) % 10 ); - STATIC_ITEM_P(PSTR("> "), SS_LEFT, buffer); // > 125m + STATIC_ITEM_F(F("> "), SS_LEFT, buffer); // > 125m #if SERVICE_INTERVAL_1 > 0 || SERVICE_INTERVAL_2 > 0 || SERVICE_INTERVAL_3 > 0 strcpy_P(buffer, GET_TEXT(MSG_SERVICE_IN)); #endif #if SERVICE_INTERVAL_1 > 0 - STATIC_ITEM_P(PSTR(SERVICE_NAME_1 " "), SS_LEFT, buffer); // Service X in: - STATIC_ITEM_P(PSTR("> "), SS_LEFT, duration_t(stats.nextService1).toString(buffer)); // > 7d 12h 11m 10s + STATIC_ITEM_F(F(SERVICE_NAME_1 " "), SS_LEFT, buffer); // Service X in: + STATIC_ITEM_F(F("> "), SS_LEFT, duration_t(stats.nextService1).toString(buffer)); // > 7d 12h 11m 10s #endif #if SERVICE_INTERVAL_2 > 0 - STATIC_ITEM_P(PSTR(SERVICE_NAME_2 " "), SS_LEFT, buffer); - STATIC_ITEM_P(PSTR("> "), SS_LEFT, duration_t(stats.nextService2).toString(buffer)); + STATIC_ITEM_F(F(SERVICE_NAME_2 " "), SS_LEFT, buffer); + STATIC_ITEM_F(F("> "), SS_LEFT, duration_t(stats.nextService2).toString(buffer)); #endif #if SERVICE_INTERVAL_3 > 0 - STATIC_ITEM_P(PSTR(SERVICE_NAME_3 " "), SS_LEFT, buffer); - STATIC_ITEM_P(PSTR("> "), SS_LEFT, duration_t(stats.nextService3).toString(buffer)); + STATIC_ITEM_F(F(SERVICE_NAME_3 " "), SS_LEFT, buffer); + STATIC_ITEM_F(F("> "), SS_LEFT, duration_t(stats.nextService3).toString(buffer)); #endif END_SCREEN(); @@ -103,7 +103,7 @@ void menu_info_thermistors() { #if HAS_EXTRUDERS #define THERMISTOR_ID TEMP_SENSOR_0 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(STR_E0 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F(STR_E0 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_0_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_0_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -113,7 +113,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_1 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(STR_E1 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F(STR_E1 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_1_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_1_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -123,7 +123,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_2 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(STR_E2 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F(STR_E2 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_2_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_2_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -133,7 +133,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_3 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(STR_E3 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F(STR_E3 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_3_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_3_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -143,7 +143,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_4 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(STR_E4 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F(STR_E4 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_4_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_4_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -153,7 +153,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_5 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(STR_E5 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F(STR_E5 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_5_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_5_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -163,7 +163,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_6 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(STR_E6 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F(STR_E6 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_6_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_6_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -173,7 +173,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_7 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(STR_E7 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F(STR_E7 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_7_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_7_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -183,7 +183,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_BED #include "../thermistornames.h" - STATIC_ITEM_P(PSTR("BED: " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F("BED: " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(BED_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(BED_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_BED, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -193,7 +193,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_CHAMBER #include "../thermistornames.h" - STATIC_ITEM_P(PSTR("CHAM: " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F("CHAM: " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(CHAMBER_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(CHAMBER_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_CHAMBER, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -203,7 +203,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_COOLER #include "../thermistornames.h" - STATIC_ITEM_P(PSTR("COOL: " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_F(F("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); @@ -219,9 +219,9 @@ void menu_info_board() { if (ui.use_click()) return ui.go_back(); START_SCREEN(); - STATIC_ITEM_P(PSTR(BOARD_INFO_NAME), SS_DEFAULT|SS_INVERT); // MyPrinterController + STATIC_ITEM_F(F(BOARD_INFO_NAME), SS_DEFAULT|SS_INVERT); // MyPrinterController #ifdef BOARD_WEBSITE_URL - STATIC_ITEM_P(PSTR(BOARD_WEBSITE_URL), SS_LEFT); // www.my3dprinter.com + STATIC_ITEM_F(F(BOARD_WEBSITE_URL), SS_LEFT); // www.my3dprinter.com #endif PSTRING_ITEM(MSG_INFO_BAUDRATE, STRINGIFY(BAUDRATE), SS_CENTER); // Baud: 250000 PSTRING_ITEM(MSG_INFO_PROTOCOL, PROTOCOL_VERSION, SS_CENTER); // Protocol: 1.0 @@ -251,11 +251,11 @@ void menu_info_board() { void menu_info_printer() { if (ui.use_click()) return ui.go_back(); START_SCREEN(); - STATIC_ITEM(MSG_MARLIN, SS_DEFAULT|SS_INVERT); // Marlin - STATIC_ITEM_P(PSTR(SHORT_BUILD_VERSION)); // x.x.x-Branch - STATIC_ITEM_P(PSTR(STRING_DISTRIBUTION_DATE)); // YYYY-MM-DD HH:MM - STATIC_ITEM_P(PSTR(MACHINE_NAME), SS_DEFAULT|SS_INVERT); // My3DPrinter - STATIC_ITEM_P(PSTR(WEBSITE_URL)); // www.my3dprinter.com + STATIC_ITEM(MSG_MARLIN, SS_DEFAULT|SS_INVERT); // Marlin + STATIC_ITEM_F(F(SHORT_BUILD_VERSION)); // x.x.x-Branch + STATIC_ITEM_F(F(STRING_DISTRIBUTION_DATE)); // YYYY-MM-DD HH:MM + STATIC_ITEM_F(F(MACHINE_NAME), SS_DEFAULT|SS_INVERT); // My3DPrinter + STATIC_ITEM_F(F(WEBSITE_URL)); // www.my3dprinter.com PSTRING_ITEM(MSG_INFO_EXTRUDERS, STRINGIFY(EXTRUDERS), SS_CENTER); // Extruders: 2 #if HAS_LEVELING STATIC_ITEM( diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index fcde9f580193..3e1733ee1c90 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -27,6 +27,10 @@ #include "../../inc/MarlinConfigPre.h" +#if ENABLED(LASER_SYNCHRONOUS_M106_M107) + #include "../../module/planner.h" +#endif + void lcd_move_z(); //////////////////////////////////////////// @@ -36,36 +40,36 @@ void lcd_move_z(); // SUBMENU(LABEL, screen_handler) class MenuItem_submenu : public MenuItemBase { public: - 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]); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, ...) { + _draw(sel, row, fstr, '>', LCD_STR_ARROW_RIGHT[0]); } - static void action(PGM_P const, const screenFunc_t func) { ui.push_current_screen(); ui.goto_screen(func); } + static void action(FSTR_P const, const screenFunc_t func) { ui.push_current_screen(); ui.goto_screen(func); } }; // Any menu item that invokes an immediate action class MenuItem_button : public MenuItemBase { public: // Button-y Items are selectable lines with no other indicator - static void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { - _draw(sel, row, pstr, '>', ' '); + static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, ...) { + _draw(sel, row, fstr, '>', ' '); } }; // ACTION_ITEM(LABEL, FUNC) class MenuItem_function : public MenuItem_button { public: - //static void action(PGM_P const, const uint8_t, const menuAction_t func) { (*func)(); }; - static void action(PGM_P const, const menuAction_t func) { if (func) (*func)(); }; + //static void action(FSTR_P const, const uint8_t, const menuAction_t func) { (*func)(); }; + static void action(FSTR_P const, const menuAction_t func) { if (func) (*func)(); }; }; // GCODES_ITEM(LABEL, GCODES) class MenuItem_gcode : public MenuItem_button { public: - FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { - _draw(sel, row, pstr, '>', ' '); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, ...) { + _draw(sel, row, fstr, '>', ' '); } - static void action(PGM_P const, PGM_P const pgcode) { queue.inject(FPSTR(pgcode)); } - static void action(PGM_P const pstr, const uint8_t, PGM_P const pgcode) { action(pstr, pgcode); } + static void action(FSTR_P const, FSTR_P const fgcode) { queue.inject(fgcode); } + static void action(FSTR_P const fstr, const uint8_t, FSTR_P const fgcode) { action(fstr, fgcode); } }; //////////////////////////////////////////// @@ -82,16 +86,16 @@ class TMenuEditItem : MenuEditItemBase { 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: - FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, type_t * const data, ...) { - MenuEditItemBase::draw(sel, row, pstr, NAME::strfunc(*(data))); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, type_t * const data, ...) { + MenuEditItemBase::draw(sel, row, fstr, NAME::strfunc(*(data))); } - FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, type_t (*pget)(), ...) { - MenuEditItemBase::draw(sel, row, pstr, NAME::strfunc(pget())); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, type_t (*pget)(), ...) { + MenuEditItemBase::draw(sel, row, fstr, NAME::strfunc(pget())); } // Edit screen for this type of item static void edit_screen() { MenuEditItemBase::edit_screen(to_string, load); } static void action( - PGM_P const pstr, // Edit label + FSTR_P const fstr, // Edit label type_t * const ptr, // Value pointer const type_t minValue, // Value range const type_t maxValue, @@ -101,7 +105,7 @@ class TMenuEditItem : MenuEditItemBase { // Make sure minv and maxv fit within int32_t const int32_t minv = _MAX(scale(minValue), INT32_MIN), maxv = _MIN(scale(maxValue), INT32_MAX); - goto_edit_screen(pstr, ptr, minv, maxv - minv, scale(*ptr) - minv, + goto_edit_screen(fstr, ptr, minv, maxv - minv, scale(*ptr) - minv, edit_screen, callback, live); } }; @@ -168,16 +172,16 @@ DEFINE_MENU_EDIT_ITEM_TYPE(long5_25 ,uint32_t ,ftostr5rj , 0.04f ); class MenuItem_bool : public MenuEditItemBase { public: - FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, const bool onoff) { - MenuEditItemBase::draw(sel, row, pstr, onoff ? GET_TEXT(MSG_LCD_ON) : GET_TEXT(MSG_LCD_OFF), true); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, const bool onoff) { + MenuEditItemBase::draw(sel, row, fstr, onoff ? GET_TEXT_F(MSG_LCD_ON) : GET_TEXT_F(MSG_LCD_OFF)); } - FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, bool * const data, ...) { - draw(sel, row, pstr, *data); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, bool * const data, ...) { + draw(sel, row, fstr, *data); } - FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, PGM_P const, bool (*pget)(), ...) { - draw(sel, row, pstr, pget()); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr, FSTR_P const, bool (*pget)(), ...) { + draw(sel, row, fstr, pget()); } - static void action(PGM_P const pstr, bool * const ptr, const screenFunc_t callbackFunc=nullptr) { + static void action(FSTR_P const fstr, bool * const ptr, const screenFunc_t callbackFunc=nullptr) { *ptr ^= true; ui.refresh(); if (callbackFunc) (*callbackFunc)(); } @@ -250,16 +254,16 @@ class MenuItem_bool : public MenuEditItemBase { * * Examples: * BACK_ITEM(MSG_INFO_SCREEN) - * MenuItem_back::action(plabel, ...) - * MenuItem_back::draw(sel, row, plabel, ...) + * MenuItem_back::action(flabel, ...) + * MenuItem_back::draw(sel, row, flabel, ...) * * ACTION_ITEM(MSG_PAUSE_PRINT, lcd_sdcard_pause) - * MenuItem_function::action(plabel, lcd_sdcard_pause) - * MenuItem_function::draw(sel, row, plabel, lcd_sdcard_pause) + * MenuItem_function::action(flabel, lcd_sdcard_pause) + * MenuItem_function::draw(sel, row, flabel, lcd_sdcard_pause) * * EDIT_ITEM(int3, MSG_SPEED, &feedrate_percentage, 10, 999) - * MenuItem_int3::action(plabel, &feedrate_percentage, 10, 999) - * MenuItem_int3::draw(sel, row, plabel, &feedrate_percentage, 10, 999) + * MenuItem_int3::action(flabel, &feedrate_percentage, 10, 999) + * MenuItem_int3::draw(sel, row, flabel, &feedrate_percentage, 10, 999) */ #if ENABLED(ENCODER_RATE_MULTIPLIER) @@ -268,52 +272,73 @@ class MenuItem_bool : public MenuEditItemBase { #define _MENU_ITEM_MULTIPLIER_CHECK(USE_MULTIPLIER) #endif -#define _MENU_INNER_P(TYPE, USE_MULTIPLIER, PLABEL, V...) do { \ - PGM_P const plabel = PLABEL; \ +#define _MENU_INNER_F(TYPE, USE_MULTIPLIER, FLABEL, V...) do { \ + FSTR_P const flabel = FLABEL; \ if (encoderLine == _thisItemNr && ui.use_click()) { \ _MENU_ITEM_MULTIPLIER_CHECK(USE_MULTIPLIER); \ - MenuItem_##TYPE::action(plabel, ##V); \ + MenuItem_##TYPE::action(flabel, ##V); \ if (ui.screen_changed) return; \ } \ if (ui.should_draw()) \ MenuItem_##TYPE::draw \ - (encoderLine == _thisItemNr, _lcdLineNr, plabel, ##V); \ + (encoderLine == _thisItemNr, _lcdLineNr, flabel, ##V); \ }while(0) -#define _MENU_ITEM_P(TYPE, V...) do { \ +// Item with optional data +#define _MENU_ITEM_F(TYPE, V...) do { \ if (_menuLineNr == _thisItemNr) { \ _skipStatic = false; \ - _MENU_INNER_P(TYPE, ##V); \ + _MENU_INNER_F(TYPE, ##V); \ } \ NEXT_ITEM(); \ }while(0) -// Indexed items set a global index value and optional data -#define _MENU_ITEM_N_S_P(TYPE, N, S, V...) do{ \ +// Item with index value, C-string, and optional data +#define _MENU_ITEM_N_S_F(TYPE, N, S, V...) do{ \ if (_menuLineNr == _thisItemNr) { \ _skipStatic = false; \ MenuItemBase::init(N, S); \ - _MENU_INNER_P(TYPE, ##V); \ + _MENU_INNER_F(TYPE, ##V); \ } \ NEXT_ITEM(); \ }while(0) -// Indexed items set a global index value -#define _MENU_ITEM_N_P(TYPE, N, V...) do{ \ +// Item with index value and F-string +#define _MENU_ITEM_N_f_F(TYPE, N, f, V...) do{ \ + if (_menuLineNr == _thisItemNr) { \ + _skipStatic = false; \ + MenuItemBase::init(N, f); \ + _MENU_INNER_F(TYPE, ##V); \ + } \ + NEXT_ITEM(); \ +}while(0) + +// Item with index value +#define _MENU_ITEM_N_F(TYPE, N, V...) do{ \ if (_menuLineNr == _thisItemNr) { \ _skipStatic = false; \ - MenuItemBase::itemIndex = N; \ - _MENU_INNER_P(TYPE, ##V); \ + MenuItemBase::init(N); \ + _MENU_INNER_F(TYPE, ##V); \ } \ NEXT_ITEM(); \ }while(0) // Items with a unique string -#define _MENU_ITEM_S_P(TYPE, S, V...) do{ \ +#define _MENU_ITEM_S_F(TYPE, S, V...) do{ \ if (_menuLineNr == _thisItemNr) { \ _skipStatic = false; \ - MenuItemBase::itemString = S; \ - _MENU_INNER_P(TYPE, ##V); \ + MenuItemBase::init(0, S); \ + _MENU_INNER_F(TYPE, ##V); \ + } \ + NEXT_ITEM(); \ +}while(0) + +// Items with a unique F-string +#define _MENU_ITEM_f_F(TYPE, f, V...) do{ \ + if (_menuLineNr == _thisItemNr) { \ + _skipStatic = false; \ + MenuItemBase::init(0, f); \ + _MENU_INNER_F(TYPE, ##V); \ } \ NEXT_ITEM(); \ }while(0) @@ -321,25 +346,25 @@ class MenuItem_bool : public MenuEditItemBase { // STATIC_ITEM draws a styled string with no highlight. // Parameters: label [, style [, char *value] ] -#define STATIC_ITEM_INNER_P(PLABEL, V...) do{ \ +#define STATIC_ITEM_INNER_F(FLABEL, V...) do{ \ if (_skipStatic && encoderLine <= _thisItemNr) { \ ui.encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; \ ++encoderLine; \ } \ if (ui.should_draw()) \ - MenuItem_static::draw(_lcdLineNr, PLABEL, ##V); \ + MenuItem_static::draw(_lcdLineNr, FLABEL, ##V); \ } while(0) -#define STATIC_ITEM_P(PLABEL, V...) do{ \ +#define STATIC_ITEM_F(FLABEL, V...) do{ \ if (_menuLineNr == _thisItemNr) \ - STATIC_ITEM_INNER_P(PLABEL, ##V); \ + STATIC_ITEM_INNER_F(FLABEL, ##V); \ NEXT_ITEM(); \ } while(0) -#define STATIC_ITEM_N_P(PLABEL, N, V...) do{ \ +#define STATIC_ITEM_N_F(N, FLABEL, V...) do{ \ if (_menuLineNr == _thisItemNr) { \ MenuItemBase::init(N); \ - STATIC_ITEM_INNER_P(PLABEL, ##V); \ + STATIC_ITEM_INNER_F(FLABEL, ##V); \ } \ NEXT_ITEM(); \ }while(0) @@ -347,126 +372,167 @@ class MenuItem_bool : public MenuEditItemBase { // PSTRING_ITEM is like STATIC_ITEM but it takes // two PSTRs with the style as the last parameter. -#define PSTRING_ITEM_P(PLABEL, PVAL, STYL) do{ \ +#define PSTRING_ITEM_F(FLABEL, PVAL, STYL) do{ \ constexpr int m = 20; \ char msg[m+1]; \ msg[0] = ':'; msg[1] = ' '; \ strncpy_P(msg+2, PSTR(PVAL), m-2); \ if (msg[m-1] & 0x80) msg[m-1] = '\0'; \ - STATIC_ITEM_P(PLABEL, STYL, msg); \ + STATIC_ITEM_F(FLABEL, STYL, msg); \ }while(0) -#define PSTRING_ITEM(LABEL, V...) PSTRING_ITEM_P(GET_TEXT(LABEL), ##V) +#define PSTRING_ITEM(LABEL, V...) PSTRING_ITEM_F(GET_TEXT_F(LABEL), ##V) + +#define STATIC_ITEM(LABEL, V...) STATIC_ITEM_F(GET_TEXT_F(LABEL), ##V) +#define STATIC_ITEM_N(N, LABEL, V...) STATIC_ITEM_N_F(N, GET_TEXT_F(LABEL), ##V) + +// Menu item with index and composed C-string substitution +#define MENU_ITEM_N_S_F(TYPE, N, S, FLABEL, V...) _MENU_ITEM_N_S_F(TYPE, N, S, false, FLABEL, ##V) +#define MENU_ITEM_N_S(TYPE, N, S, LABEL, V...) MENU_ITEM_N_S_F(TYPE, N, S, GET_TEXT_F(LABEL), ##V) + +// Menu item with composed C-string substitution +#define MENU_ITEM_S_F(TYPE, S, FLABEL, V...) _MENU_ITEM_S_F(TYPE, S, false, FLABEL, ##V) +#define MENU_ITEM_S(TYPE, S, LABEL, V...) MENU_ITEM_S_F(TYPE, S, GET_TEXT_F(LABEL), ##V) + +// Menu item substitution, indexed +#define MENU_ITEM_N_F(TYPE, N, FLABEL, V...) _MENU_ITEM_N_F(TYPE, N, false, FLABEL, ##V) +#define MENU_ITEM_N(TYPE, N, LABEL, V...) MENU_ITEM_N_F(TYPE, N, GET_TEXT_F(LABEL), ##V) -#define STATIC_ITEM(LABEL, V...) STATIC_ITEM_P(GET_TEXT(LABEL), ##V) -#define STATIC_ITEM_N(LABEL, N, V...) STATIC_ITEM_N_P(GET_TEXT(LABEL), N, ##V) +// Basic menu items, no substitution +#define MENU_ITEM_F(TYPE, FLABEL, V...) _MENU_ITEM_F(TYPE, false, FLABEL, ##V) +#define MENU_ITEM(TYPE, LABEL, V...) MENU_ITEM_F(TYPE, GET_TEXT_F(LABEL), ##V) -#define MENU_ITEM_N_S_P(TYPE, N, S, PLABEL, V...) _MENU_ITEM_N_S_P(TYPE, N, S, false, PLABEL, ##V) -#define MENU_ITEM_N_S(TYPE, N, S, LABEL, V...) MENU_ITEM_N_S_P(TYPE, N, S, GET_TEXT(LABEL), ##V) -#define MENU_ITEM_S_P(TYPE, S, PLABEL, V...) _MENU_ITEM_S_P(TYPE, S, false, PLABEL, ##V) -#define MENU_ITEM_S(TYPE, S, LABEL, V...) MENU_ITEM_S_P(TYPE, S, GET_TEXT(LABEL), ##V) -#define MENU_ITEM_N_P(TYPE, N, PLABEL, V...) _MENU_ITEM_N_P(TYPE, N, false, PLABEL, ##V) -#define MENU_ITEM_N(TYPE, N, LABEL, V...) MENU_ITEM_N_P(TYPE, N, GET_TEXT(LABEL), ##V) -#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) +// Predefined menu item types // -#define BACK_ITEM_P(PLABEL) MENU_ITEM_P(back, PLABEL) +#define BACK_ITEM_F(FLABEL) MENU_ITEM_F(back, FLABEL) #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) -#define ACTION_ITEM_N_S(N, S, LABEL, ACTION) ACTION_ITEM_N_S_P(N, S, GET_TEXT(LABEL), ACTION) -#define ACTION_ITEM_S_P(S, PLABEL, ACTION) MENU_ITEM_S_P(function, S, PLABEL, ACTION) -#define ACTION_ITEM_S(S, LABEL, ACTION) ACTION_ITEM_S_P(S, GET_TEXT(LABEL), ACTION) -#define ACTION_ITEM_N_P(N, PLABEL, ACTION) MENU_ITEM_N_P(function, N, PLABEL, ACTION) -#define ACTION_ITEM_N(N, LABEL, ACTION) ACTION_ITEM_N_P(N, GET_TEXT(LABEL), ACTION) -#define ACTION_ITEM_P(PLABEL, ACTION) MENU_ITEM_P(function, PLABEL, ACTION) -#define ACTION_ITEM(LABEL, ACTION) ACTION_ITEM_P(GET_TEXT(LABEL), ACTION) - -#define GCODES_ITEM_N_S_P(N, S, PLABEL, GCODES) MENU_ITEM_N_S_P(gcode, N, S, PLABEL, GCODES) -#define GCODES_ITEM_N_S(N, S, LABEL, GCODES) GCODES_ITEM_N_S_P(N, S, GET_TEXT(LABEL), GCODES) -#define GCODES_ITEM_S_P(S, PLABEL, GCODES) MENU_ITEM_S_P(gcode, S, PLABEL, GCODES) -#define GCODES_ITEM_S(S, LABEL, GCODES) GCODES_ITEM_S_P(S, GET_TEXT(LABEL), GCODES) -#define GCODES_ITEM_N_P(N, PLABEL, GCODES) MENU_ITEM_N_P(gcode, N, PLABEL, GCODES) -#define GCODES_ITEM_N(N, LABEL, GCODES) GCODES_ITEM_N_P(N, GET_TEXT(LABEL), GCODES) -#define GCODES_ITEM_P(PLABEL, GCODES) MENU_ITEM_P(gcode, PLABEL, GCODES) -#define GCODES_ITEM(LABEL, GCODES) GCODES_ITEM_P(GET_TEXT(LABEL), GCODES) - -#define SUBMENU_N_S_P(N, S, PLABEL, DEST) MENU_ITEM_N_S_P(submenu, N, S, PLABEL, DEST) -#define SUBMENU_N_S(N, S, LABEL, DEST) SUBMENU_N_S_P(N, S, GET_TEXT(LABEL), DEST) -#define SUBMENU_S_P(S, PLABEL, DEST) MENU_ITEM_S_P(submenu, S, PLABEL, DEST) -#define SUBMENU_S(S, LABEL, DEST) SUBMENU_S_P(S, GET_TEXT(LABEL), DEST) -#define SUBMENU_N_P(N, PLABEL, DEST) MENU_ITEM_N_P(submenu, N, PLABEL, DEST) -#define SUBMENU_N(N, LABEL, DEST) SUBMENU_N_P(N, GET_TEXT(LABEL), DEST) -#define SUBMENU_P(PLABEL, DEST) MENU_ITEM_P(submenu, PLABEL, DEST) -#define SUBMENU(LABEL, DEST) SUBMENU_P(GET_TEXT(LABEL), DEST) - -#define EDIT_ITEM_N_S_P(TYPE, N, S, PLABEL, V...) MENU_ITEM_N_S_P(TYPE, N, S, PLABEL, ##V) -#define EDIT_ITEM_N_S(TYPE, N, S, LABEL, V...) EDIT_ITEM_N_S_P(TYPE, N, S, GET_TEXT(LABEL), ##V) -#define EDIT_ITEM_S_P(TYPE, S, PLABEL, V...) MENU_ITEM_S_P(TYPE, S, PLABEL, ##V) -#define EDIT_ITEM_S(TYPE, S, LABEL, V...) EDIT_ITEM_S_P(TYPE, S, GET_TEXT(LABEL), ##V) -#define EDIT_ITEM_N_P(TYPE, N, PLABEL, V...) MENU_ITEM_N_P(TYPE, N, PLABEL, ##V) -#define EDIT_ITEM_N(TYPE, N, LABEL, V...) EDIT_ITEM_N_P(TYPE, N, GET_TEXT(LABEL), ##V) -#define EDIT_ITEM_P(TYPE, PLABEL, V...) MENU_ITEM_P(TYPE, PLABEL, ##V) -#define EDIT_ITEM(TYPE, LABEL, V...) EDIT_ITEM_P(TYPE, GET_TEXT(LABEL), ##V) - -#define EDIT_ITEM_FAST_N_S_P(TYPE, N, S, PLABEL, V...) _MENU_ITEM_N_S_P(TYPE, N, S, true, PLABEL, ##V) -#define EDIT_ITEM_FAST_N_S(TYPE, N, S, LABEL, V...) EDIT_ITEM_FAST_N_S_P(TYPE, N, S, true, GET_TEXT(LABEL), ##V) -#define EDIT_ITEM_FAST_S_P(TYPE, S, PLABEL, V...) _MENU_ITEM_S_P(TYPE, S, true, PLABEL, ##V) -#define EDIT_ITEM_FAST_S(TYPE, S, LABEL, V...) EDIT_ITEM_FAST_S_P(TYPE, S, GET_TEXT(LABEL), ##V) -#define EDIT_ITEM_FAST_N_P(TYPE, N, PLABEL, V...) _MENU_ITEM_N_P(TYPE, N, true, PLABEL, ##V) -#define EDIT_ITEM_FAST_N(TYPE, N, LABEL, V...) EDIT_ITEM_FAST_N_P(TYPE, N, GET_TEXT(LABEL), ##V) -#define EDIT_ITEM_FAST_P(TYPE, PLABEL, V...) _MENU_ITEM_P(TYPE, true, PLABEL, ##V) -#define EDIT_ITEM_FAST(TYPE, LABEL, V...) EDIT_ITEM_FAST_P(TYPE, GET_TEXT(LABEL), ##V) - -#define _CONFIRM_ITEM_INNER_P(PLABEL, V...) do { \ +#define ACTION_ITEM_N_S_F(N, S, FLABEL, ACTION) MENU_ITEM_N_S_F(function, N, S, FLABEL, ACTION) +#define ACTION_ITEM_N_S(N, S, LABEL, ACTION) ACTION_ITEM_N_S_F(N, S, GET_TEXT_F(LABEL), ACTION) +#define ACTION_ITEM_S_F(S, FLABEL, ACTION) MENU_ITEM_S_F(function, S, FLABEL, ACTION) +#define ACTION_ITEM_S(S, LABEL, ACTION) ACTION_ITEM_S_F(S, GET_TEXT_F(LABEL), ACTION) +#define ACTION_ITEM_N_F(N, FLABEL, ACTION) MENU_ITEM_N_F(function, N, FLABEL, ACTION) +#define ACTION_ITEM_N(N, LABEL, ACTION) ACTION_ITEM_N_F(N, GET_TEXT_F(LABEL), ACTION) +#define ACTION_ITEM_F(FLABEL, ACTION) MENU_ITEM_F(function, FLABEL, ACTION) +#define ACTION_ITEM(LABEL, ACTION) ACTION_ITEM_F(GET_TEXT_F(LABEL), ACTION) + +#define GCODES_ITEM_N_S_F(N, S, FLABEL, GCODES) MENU_ITEM_N_S_F(gcode, N, S, FLABEL, GCODES) +#define GCODES_ITEM_N_S(N, S, LABEL, GCODES) GCODES_ITEM_N_S_F(N, S, GET_TEXT_F(LABEL), GCODES) +#define GCODES_ITEM_S_F(S, FLABEL, GCODES) MENU_ITEM_S_F(gcode, S, FLABEL, GCODES) +#define GCODES_ITEM_S(S, LABEL, GCODES) GCODES_ITEM_S_F(S, GET_TEXT_F(LABEL), GCODES) +#define GCODES_ITEM_N_F(N, FLABEL, GCODES) MENU_ITEM_N_F(gcode, N, FLABEL, GCODES) +#define GCODES_ITEM_N(N, LABEL, GCODES) GCODES_ITEM_N_F(N, GET_TEXT_F(LABEL), GCODES) +#define GCODES_ITEM_F(FLABEL, GCODES) MENU_ITEM_F(gcode, FLABEL, GCODES) +#define GCODES_ITEM(LABEL, GCODES) GCODES_ITEM_F(GET_TEXT_F(LABEL), GCODES) + +#define SUBMENU_N_S_F(N, S, FLABEL, DEST) MENU_ITEM_N_S_F(submenu, N, S, FLABEL, DEST) +#define SUBMENU_N_S(N, S, LABEL, DEST) SUBMENU_N_S_F(N, S, GET_TEXT_F(LABEL), DEST) +#define SUBMENU_S_F(S, FLABEL, DEST) MENU_ITEM_S_F(submenu, S, FLABEL, DEST) +#define SUBMENU_S(S, LABEL, DEST) SUBMENU_S_F(S, GET_TEXT_F(LABEL), DEST) +#define SUBMENU_N_F(N, FLABEL, DEST) MENU_ITEM_N_F(submenu, N, FLABEL, DEST) +#define SUBMENU_N(N, LABEL, DEST) SUBMENU_N_F(N, GET_TEXT_F(LABEL), DEST) +#define SUBMENU_F(FLABEL, DEST) MENU_ITEM_F(submenu, FLABEL, DEST) +#define SUBMENU(LABEL, DEST) SUBMENU_F(GET_TEXT_F(LABEL), DEST) + +#define EDIT_ITEM_N_S_F(TYPE, N, S, FLABEL, V...) MENU_ITEM_N_S_F(TYPE, N, S, FLABEL, ##V) +#define EDIT_ITEM_N_S(TYPE, N, S, LABEL, V...) EDIT_ITEM_N_S_F(TYPE, N, S, GET_TEXT_F(LABEL), ##V) +#define EDIT_ITEM_S_F(TYPE, S, FLABEL, V...) MENU_ITEM_S_F(TYPE, S, FLABEL, ##V) +#define EDIT_ITEM_S(TYPE, S, LABEL, V...) EDIT_ITEM_S_F(TYPE, S, GET_TEXT_F(LABEL), ##V) +#define EDIT_ITEM_N_F(TYPE, N, FLABEL, V...) MENU_ITEM_N_F(TYPE, N, FLABEL, ##V) +#define EDIT_ITEM_N(TYPE, N, LABEL, V...) EDIT_ITEM_N_F(TYPE, N, GET_TEXT_F(LABEL), ##V) +#define EDIT_ITEM_F(TYPE, FLABEL, V...) MENU_ITEM_F(TYPE, FLABEL, ##V) +#define EDIT_ITEM(TYPE, LABEL, V...) EDIT_ITEM_F(TYPE, GET_TEXT_F(LABEL), ##V) + +#define EDIT_ITEM_FAST_N_S_F(TYPE, N, S, FLABEL, V...) _MENU_ITEM_N_S_F(TYPE, N, S, true, FLABEL, ##V) +#define EDIT_ITEM_FAST_N_S(TYPE, N, S, LABEL, V...) EDIT_ITEM_FAST_N_S_F(TYPE, N, S, true, GET_TEXT_F(LABEL), ##V) +#define EDIT_ITEM_FAST_S_F(TYPE, S, FLABEL, V...) _MENU_ITEM_S_F(TYPE, S, true, FLABEL, ##V) +#define EDIT_ITEM_FAST_S(TYPE, S, LABEL, V...) EDIT_ITEM_FAST_S_F(TYPE, S, GET_TEXT_F(LABEL), ##V) +#define EDIT_ITEM_FAST_N_F(TYPE, N, FLABEL, V...) _MENU_ITEM_N_F(TYPE, N, true, FLABEL, ##V) +#define EDIT_ITEM_FAST_N(TYPE, N, LABEL, V...) EDIT_ITEM_FAST_N_F(TYPE, N, GET_TEXT_F(LABEL), ##V) +#define EDIT_ITEM_FAST_F(TYPE, FLABEL, V...) _MENU_ITEM_F(TYPE, true, FLABEL, ##V) +#define EDIT_ITEM_FAST(TYPE, LABEL, V...) EDIT_ITEM_FAST_F(TYPE, GET_TEXT_F(LABEL), ##V) + +// F-string substitution instead of C-string // + +#define MENU_ITEM_N_f_F(TYPE, N, f, FLABEL, V...) _MENU_ITEM_N_f_F(TYPE, N, f, false, FLABEL, ##V) +#define MENU_ITEM_N_f(TYPE, N, f, LABEL, V...) MENU_ITEM_N_f_F(TYPE, N, f, GET_TEXT_F(LABEL), ##V) +#define MENU_ITEM_f_F(TYPE, f, FLABEL, V...) _MENU_ITEM_f_F(TYPE, f, false, FLABEL, ##V) +#define MENU_ITEM_f(TYPE, f, LABEL, V...) MENU_ITEM_f_F(TYPE, f, GET_TEXT_F(LABEL), ##V) + +#define ACTION_ITEM_N_f_F(N, f, FLABEL, ACTION) MENU_ITEM_N_f_F(function, N, f, FLABEL, ACTION) +#define ACTION_ITEM_N_f(N, f, LABEL, ACTION) ACTION_ITEM_N_f_F(N, f, GET_TEXT_F(LABEL), ACTION) +#define ACTION_ITEM_f_F(f, FLABEL, ACTION) MENU_ITEM_f_F(function, f, FLABEL, ACTION) +#define ACTION_ITEM_f(f, LABEL, ACTION) ACTION_ITEM_f_F(f, GET_TEXT_F(LABEL), ACTION) + +#define GCODES_ITEM_N_f_F(N, f, FLABEL, GCODES) MENU_ITEM_N_f_F(gcode, N, f, FLABEL, GCODES) +#define GCODES_ITEM_N_f(N, f, LABEL, GCODES) GCODES_ITEM_N_f_F(N, f, GET_TEXT_F(LABEL), GCODES) +#define GCODES_ITEM_f_F(f, FLABEL, GCODES) MENU_ITEM_f_F(gcode, f, FLABEL, GCODES) +#define GCODES_ITEM_f(f, LABEL, GCODES) GCODES_ITEM_f_F(f, GET_TEXT_F(LABEL), GCODES) + +#define SUBMENU_N_f_F(N, f, FLABEL, DEST) MENU_ITEM_N_f_F(submenu, N, f, FLABEL, DEST) +#define SUBMENU_N_f(N, f, LABEL, DEST) SUBMENU_N_f_F(N, f, GET_TEXT_F(LABEL), DEST) +#define SUBMENU_f_F(f, FLABEL, DEST) MENU_ITEM_f_F(submenu, f, FLABEL, DEST) +#define SUBMENU_f(f, LABEL, DEST) SUBMENU_f_F(f, GET_TEXT_F(LABEL), DEST) + +#define EDIT_ITEM_N_f_F(TYPE, N, f, FLABEL, V...) MENU_ITEM_N_f_F(TYPE, N, f, FLABEL, ##V) +#define EDIT_ITEM_N_f(TYPE, N, f, LABEL, V...) EDIT_ITEM_N_f_F(TYPE, N, f, GET_TEXT_F(LABEL), ##V) +#define EDIT_ITEM_f_F(TYPE, f, FLABEL, V...) MENU_ITEM_f_F(TYPE, f, FLABEL, ##V) +#define EDIT_ITEM_f(TYPE, f, LABEL, V...) EDIT_ITEM_f_F(TYPE, f, GET_TEXT_F(LABEL), ##V) + +#define EDIT_ITEM_FAST_N_f_F(TYPE, N, f, FLABEL, V...) _MENU_ITEM_N_f_F(TYPE, N, f, true, FLABEL, ##V) +#define EDIT_ITEM_FAST_N_f(TYPE, N, f, LABEL, V...) EDIT_ITEM_FAST_N_f_F(TYPE, N, f, true, GET_TEXT_F(LABEL), ##V) +#define EDIT_ITEM_FAST_f_F(TYPE, f, FLABEL, V...) _MENU_ITEM_f_F(TYPE, f, true, FLABEL, ##V) +#define EDIT_ITEM_FAST_f(TYPE, f, LABEL, V...) EDIT_ITEM_FAST_f_F(TYPE, f, GET_TEXT_F(LABEL), ##V) + +#define _CONFIRM_ITEM_INNER_F(FLABEL, V...) do { \ if (encoderLine == _thisItemNr && ui.use_click()) { \ ui.push_current_screen(); \ ui.goto_screen([]{MenuItem_confirm::select_screen(V);}); \ return; \ } \ if (ui.should_draw()) MenuItem_confirm::draw \ - (encoderLine == _thisItemNr, _lcdLineNr, PLABEL, ##V); \ + (encoderLine == _thisItemNr, _lcdLineNr, FLABEL, ##V); \ }while(0) // Indexed items set a global index value and optional data -#define _CONFIRM_ITEM_P(PLABEL, V...) do { \ +#define _CONFIRM_ITEM_F(FLABEL, V...) do { \ if (_menuLineNr == _thisItemNr) { \ _skipStatic = false; \ - _CONFIRM_ITEM_INNER_P(PLABEL, ##V); \ + _CONFIRM_ITEM_INNER_F(FLABEL, ##V); \ } \ NEXT_ITEM(); \ }while(0) // Indexed items set a global index value -#define _CONFIRM_ITEM_N_S_P(N, S, V...) do{ \ +#define _CONFIRM_ITEM_N_S_F(N, S, V...) do{ \ if (_menuLineNr == _thisItemNr) { \ _skipStatic = false; \ MenuItemBase::init(N, S); \ - _CONFIRM_ITEM_INNER_P(TYPE, ##V); \ + _CONFIRM_ITEM_INNER_F(TYPE, ##V); \ } \ NEXT_ITEM(); \ }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_F(N, V...) _CONFIRM_ITEM_N_S_F(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_F(FLABEL,A,B,V...) _CONFIRM_ITEM_F(FLABEL, GET_TEXT_F(A), GET_TEXT_F(B), ##V) +#define CONFIRM_ITEM(LABEL, V...) CONFIRM_ITEM_F(GET_TEXT_F(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 YESNO_ITEM_F(FLABEL, V...) CONFIRM_ITEM_F(FLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM(LABEL, V...) YESNO_ITEM_F(GET_TEXT_F(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 CONFIRM_ITEM_N_S_F(N,S,FLABEL,A,B,V...) _CONFIRM_ITEM_N_S_F(N, S, FLABEL, GET_TEXT_F(A), GET_TEXT_F(B), ##V) +#define CONFIRM_ITEM_N_S(N,S,LABEL,V...) CONFIRM_ITEM_N_S_F(N, S, GET_TEXT_F(LABEL), ##V) +#define CONFIRM_ITEM_N_F(N,FLABEL,A,B,V...) _CONFIRM_ITEM_N_F(N, FLABEL, GET_TEXT_F(A), GET_TEXT_F(B), ##V) +#define CONFIRM_ITEM_N(N,LABEL, V...) CONFIRM_ITEM_N_F(N, GET_TEXT_F(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) +#define YESNO_ITEM_N_S_F(N,S,FLABEL, V...) _CONFIRM_ITEM_N_S_F(N, S, FLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM_N_S(N,S,LABEL, V...) YESNO_ITEM_N_S_F(N, S, GET_TEXT_F(LABEL), ##V) +#define YESNO_ITEM_N_F(N,FLABEL, V...) CONFIRM_ITEM_N_F(N, FLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM_N(N,LABEL, V...) YESNO_ITEM_N_F(N, GET_TEXT_F(LABEL), ##V) -#if ENABLED(LEVEL_BED_CORNERS) +#if ENABLED(LCD_BED_TRAMMING) void _lcd_level_bed_corners(); #endif @@ -476,6 +542,7 @@ class MenuItem_bool : public MenuEditItemBase { inline void on_fan_update() { thermalManager.set_fan_speed(MenuItemBase::itemIndex, editable.uint8); + TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS)); } #if ENABLED(EXTRA_FAN_SPEED) diff --git a/Marlin/src/lcd/menu/menu_language.cpp b/Marlin/src/lcd/menu/menu_language.cpp index 4c4b7880f2c3..2ea4359c6bb7 100644 --- a/Marlin/src/lcd/menu/menu_language.cpp +++ b/Marlin/src/lcd/menu/menu_language.cpp @@ -41,14 +41,14 @@ 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); }); + MENU_ITEM_F(function, FPSTR(GET_LANGUAGE_NAME(1)), []{ set_lcd_language(0); }); + MENU_ITEM_F(function, FPSTR(GET_LANGUAGE_NAME(2)), []{ set_lcd_language(1); }); #if NUM_LANGUAGES > 2 - MENU_ITEM_P(function, GET_LANG(LCD_LANGUAGE_3)::LANGUAGE, []{ set_lcd_language(2); }); + MENU_ITEM_F(function, FPSTR(GET_LANGUAGE_NAME(3)), []{ set_lcd_language(2); }); #if NUM_LANGUAGES > 3 - MENU_ITEM_P(function, GET_LANG(LCD_LANGUAGE_4)::LANGUAGE, []{ set_lcd_language(3); }); + MENU_ITEM_F(function, FPSTR(GET_LANGUAGE_NAME(4)), []{ set_lcd_language(3); }); #if NUM_LANGUAGES > 4 - MENU_ITEM_P(function, GET_LANG(LCD_LANGUAGE_5)::LANGUAGE, []{ set_lcd_language(4); }); + MENU_ITEM_F(function, FPSTR(GET_LANGUAGE_NAME(5)), []{ set_lcd_language(4); }); #endif #endif #endif diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index 0c08f6fa944b..867e4dafa940 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -83,7 +83,7 @@ START_MENU(); BACK_ITEM(MSG_LED_CONTROL); #if ENABLED(NEOPIXEL2_SEPARATE) - STATIC_ITEM_N(MSG_LED_CHANNEL_N, 1, SS_DEFAULT|SS_INVERT); + STATIC_ITEM_N(1, MSG_LED_CHANNEL_N, SS_DEFAULT|SS_INVERT); #endif 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); @@ -95,7 +95,7 @@ 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); + STATIC_ITEM_N(2, MSG_LED_CHANNEL_N, 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); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index a15653589523..518f1e0f502d 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -124,13 +124,13 @@ void menu_configuration(); #define _DONE_SCRIPT "" #endif #define GCODE_LAMBDA_MAIN(N) []{ _lcd_custom_menu_main_gcode(F(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), nullptr, \ - PSTR(MAIN_MENU_ITEM_##N##_DESC "?") \ - ); \ + #define _CUSTOM_ITEM_MAIN(N) ACTION_ITEM_F(F(MAIN_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_MAIN(N)); + #define _CUSTOM_ITEM_MAIN_CONFIRM(N) \ + SUBMENU_F(F(MAIN_MENU_ITEM_##N##_DESC), []{ \ + MenuItem_confirm::confirm_screen( \ + GCODE_LAMBDA_MAIN(N), nullptr, \ + F(MAIN_MENU_ITEM_##N##_DESC "?") \ + ); \ }) #define CUSTOM_ITEM_MAIN(N) do{ \ @@ -246,11 +246,11 @@ void menu_main() { if (card_detected) { if (!card_open) { - #if PIN_EXISTS(SD_DETECT) - GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); // M21 Change Media - #else // - or - - ACTION_ITEM(MSG_RELEASE_MEDIA, []{ // M22 Release Media - queue.inject(PSTR("M22")); + #if HAS_SD_DETECT + GCODES_ITEM(MSG_CHANGE_MEDIA, F("M21")); // M21 Change Media + #else // - or - + ACTION_ITEM(MSG_RELEASE_MEDIA, []{ // M22 Release Media + queue.inject(F("M22")); #if ENABLED(TFT_COLOR_UI) // Menu display issue on item removal with multi language selection menu if (encoderTopLine > 0) encoderTopLine--; @@ -258,14 +258,14 @@ void menu_main() { #endif }); #endif - SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); // Media Menu (or Password First) + 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" + #if HAS_SD_DETECT + ACTION_ITEM(MSG_NO_MEDIA, nullptr); // "No Media" #else - GCODES_ITEM(MSG_ATTACH_MEDIA, PSTR("M21")); // M21 Attach Media + GCODES_ITEM(MSG_ATTACH_MEDIA, F("M21")); // M21 Attach Media #endif } }; @@ -279,9 +279,9 @@ void menu_main() { #if MACHINE_CAN_STOP SUBMENU(MSG_STOP_PRINT, []{ MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_STOP), GET_TEXT(MSG_BACK), + GET_TEXT_F(MSG_BUTTON_STOP), GET_TEXT_F(MSG_BACK), ui.abort_print, nullptr, - GET_TEXT(MSG_STOP_PRINT), (const char *)nullptr, PSTR("?") + GET_TEXT_F(MSG_STOP_PRINT), (const char *)nullptr, F("?") ); }); #endif @@ -342,7 +342,7 @@ void menu_main() { #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); + SUBMENU_F(F(CUSTOM_MENU_MAIN_TITLE), custom_menus_main); #else SUBMENU(MSG_CUSTOM_COMMANDS, custom_menus_main); #endif @@ -353,7 +353,7 @@ void menu_main() { #if E_STEPPERS == 1 && DISABLED(FILAMENT_LOAD_UNLOAD_GCODES) YESNO_ITEM(MSG_FILAMENTCHANGE, menu_change_filament, nullptr, - GET_TEXT(MSG_FILAMENTCHANGE), (const char *)nullptr, PSTR("?") + GET_TEXT_F(MSG_FILAMENTCHANGE), (const char *)nullptr, F("?") ); #else SUBMENU(MSG_FILAMENTCHANGE, menu_change_filament); @@ -377,13 +377,13 @@ void menu_main() { CONFIRM_ITEM(MSG_SWITCH_PS_OFF, MSG_YES, MSG_NO, ui.poweroff, nullptr, - GET_TEXT(MSG_SWITCH_PS_OFF), (const char *)nullptr, PSTR("?") + GET_TEXT_F(MSG_SWITCH_PS_OFF), (const char *)nullptr, F("?") ); #else ACTION_ITEM(MSG_SWITCH_PS_OFF, ui.poweroff); #endif else - GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80")); + GCODES_ITEM(MSG_SWITCH_PS_ON, F("M80")); #endif #if ENABLED(SDSUPPORT) && DISABLED(MEDIA_MENU_AT_TOP) @@ -398,24 +398,24 @@ void menu_main() { ui.return_to_status(); }; #if SERVICE_INTERVAL_1 > 0 - CONFIRM_ITEM_P(PSTR(SERVICE_NAME_1), + CONFIRM_ITEM_F(F(SERVICE_NAME_1), MSG_BUTTON_RESET, MSG_BUTTON_CANCEL, []{ _service_reset(1); }, nullptr, - GET_TEXT(MSG_SERVICE_RESET), F(SERVICE_NAME_1), PSTR("?") + GET_TEXT_F(MSG_SERVICE_RESET), F(SERVICE_NAME_1), F("?") ); #endif #if SERVICE_INTERVAL_2 > 0 - CONFIRM_ITEM_P(PSTR(SERVICE_NAME_2), + CONFIRM_ITEM_F(F(SERVICE_NAME_2), MSG_BUTTON_RESET, MSG_BUTTON_CANCEL, []{ _service_reset(2); }, nullptr, - GET_TEXT(MSG_SERVICE_RESET), F(SERVICE_NAME_2), PSTR("?") + GET_TEXT_F(MSG_SERVICE_RESET), F(SERVICE_NAME_2), F("?") ); #endif #if SERVICE_INTERVAL_3 > 0 - CONFIRM_ITEM_P(PSTR(SERVICE_NAME_3), + CONFIRM_ITEM_F(F(SERVICE_NAME_3), MSG_BUTTON_RESET, MSG_BUTTON_CANCEL, []{ _service_reset(3); }, nullptr, - GET_TEXT(MSG_SERVICE_RESET), F(SERVICE_NAME_3), PSTR("?") + GET_TEXT_F(MSG_SERVICE_RESET), F(SERVICE_NAME_3), F("?") ); #endif #endif @@ -451,9 +451,9 @@ void menu_main() { #if ENABLED(HOST_SHUTDOWN_MENU_ITEM) && defined(SHUTDOWN_ACTION) SUBMENU(MSG_HOST_SHUTDOWN, []{ MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_PROCEED), GET_TEXT(MSG_BUTTON_CANCEL), + GET_TEXT_F(MSG_BUTTON_PROCEED), GET_TEXT_F(MSG_BUTTON_CANCEL), []{ ui.return_to_status(); hostui.shutdown(); }, nullptr, - GET_TEXT(MSG_HOST_SHUTDOWN), (const char *)nullptr, PSTR("?") + GET_TEXT_F(MSG_HOST_SHUTDOWN), (const char *)nullptr, F("?") ); }); #endif diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index db1baa9bee6f..20ef6e3d198f 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -61,10 +61,10 @@ inline void sdcard_start_selected_file() { class MenuItem_sdfile : public MenuItem_sdbase { public: - static inline void draw(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard) { - MenuItem_sdbase::draw(sel, row, pstr, theCard, false); + static inline void draw(const bool sel, const uint8_t row, FSTR_P const fstr, CardReader &theCard) { + MenuItem_sdbase::draw(sel, row, fstr, theCard, false); } - static void action(PGM_P const pstr, CardReader &) { + static void action(FSTR_P const fstr, CardReader &) { #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) // Save menu state for the selected file sd_encoder_position = ui.encoderPosition; @@ -72,30 +72,30 @@ class MenuItem_sdfile : public MenuItem_sdbase { sd_items = screen_items; #endif #if ENABLED(SD_MENU_CONFIRM_START) - MenuItem_submenu::action(pstr, []{ + MenuItem_submenu::action(fstr, []{ char * const longest = card.longest_filename(); char buffer[strlen(longest) + 2]; buffer[0] = ' '; strcpy(buffer + 1, longest); MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_PRINT), GET_TEXT(MSG_BUTTON_CANCEL), + GET_TEXT_F(MSG_BUTTON_PRINT), GET_TEXT_F(MSG_BUTTON_CANCEL), sdcard_start_selected_file, nullptr, - GET_TEXT(MSG_START_PRINT), buffer, PSTR("?") + GET_TEXT_F(MSG_START_PRINT), buffer, F("?") ); }); #else sdcard_start_selected_file(); - UNUSED(pstr); + UNUSED(fstr); #endif } }; class MenuItem_sdfolder : public MenuItem_sdbase { public: - static inline void draw(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard) { - MenuItem_sdbase::draw(sel, row, pstr, theCard, true); + static inline void draw(const bool sel, const uint8_t row, FSTR_P const fstr, CardReader &theCard) { + MenuItem_sdbase::draw(sel, row, fstr, theCard, true); } - static void action(PGM_P const, CardReader &theCard) { + static void action(FSTR_P const, CardReader &theCard) { card.cd(theCard.filename); encoderTopLine = 0; ui.encoderPosition = 2 * (ENCODER_STEPS_PER_MENU_ITEM); @@ -119,15 +119,15 @@ void menu_media_filelist() { #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)); + BACK_ITEM_F(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT_F(MSG_MAIN) : GET_TEXT_F(MSG_BACK)); #endif if (card.flag.workDirIsRoot) { - #if !PIN_EXISTS(SD_DETECT) + #if !HAS_SD_DETECT ACTION_ITEM(MSG_REFRESH, []{ encoderTopLine = 0; card.mount(); }); #endif } else if (card.isMounted()) - ACTION_ITEM_P(PSTR(LCD_STR_FOLDER " .."), lcd_sd_updir); + ACTION_ITEM_F(F(LCD_STR_FOLDER " .."), lcd_sd_updir); if (ui.should_draw()) for (uint16_t i = 0; i < fileCnt; i++) { if (_menuLineNr == _thisItemNr) { @@ -146,7 +146,7 @@ void menu_media_filelist() { #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)); + BACK_ITEM_F(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT_F(MSG_MAIN) : GET_TEXT_F(MSG_BACK)); #if ENABLED(VOLUME_SD_ONBOARD) ACTION_ITEM(MSG_SD_CARD, []{ card.changeMedia(&card.media_driver_sdcard); card.mount(); ui.goto_screen(menu_media_filelist); }); #endif diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index f91f62ef8393..feb4c59f181c 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -89,15 +89,15 @@ char tmp[18]; - PGM_P const slabel = GET_TEXT(MSG_START_Z); - SUBMENU_P(slabel, []{ _lcd_mixer_gradient_z_edit(false); }); + FSTR_P const slabel = GET_TEXT_F(MSG_START_Z); + SUBMENU_F(slabel, []{ _lcd_mixer_gradient_z_edit(false); }); MENU_ITEM_ADDON_START_RJ(11); sprintf_P(tmp, PSTR("%4d.%d mm"), int(mixer.gradient.start_z), int(mixer.gradient.start_z * 10) % 10); lcd_put_u8str(tmp); MENU_ITEM_ADDON_END(); - PGM_P const elabel = GET_TEXT(MSG_END_Z); - SUBMENU_P(elabel, []{ _lcd_mixer_gradient_z_edit(true); }); + FSTR_P const elabel = GET_TEXT_F(MSG_END_Z); + SUBMENU_F(elabel, []{ _lcd_mixer_gradient_z_edit(true); }); MENU_ITEM_ADDON_START_RJ(11); sprintf_P(tmp, PSTR("%4d.%d mm"), int(mixer.gradient.end_z), int(mixer.gradient.end_z * 10) % 10); lcd_put_u8str(tmp); @@ -257,7 +257,7 @@ void menu_mixer() { ui.return_to_status(); }, nullptr, - GET_TEXT(MSG_RESET_VTOOLS), (const char *)nullptr, PSTR("?") + GET_TEXT_F(MSG_RESET_VTOOLS), (const char *)nullptr, F("?") ); #if ENABLED(GRADIENT_MIX) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 1ef38c014bd4..3765fe1e4a47 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -35,29 +35,22 @@ #include "../../module/motion.h" #include "../../gcode/parser.h" // for inch support +#include "../../module/temperature.h" #if ENABLED(DELTA) #include "../../module/delta.h" #endif -#if ENABLED(PREVENT_COLD_EXTRUSION) - #include "../../module/temperature.h" -#endif - #if HAS_LEVELING #include "../../module/planner.h" #include "../../feature/bedlevel/bedlevel.h" #endif -#if ENABLED(MANUAL_E_MOVES_RELATIVE) - float manual_move_e_origin = 0; -#endif - // // "Motion" > "Move Axis" submenu // -static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { +void lcd_move_axis(const AxisEnum axis) { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); if (ui.encoderPosition && !ui.manual_move.processing) { // Get motion limit from software endstops, if any @@ -84,37 +77,15 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { 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)); + MenuEditItemBase::draw_edit_screen(GET_TEXT_F(MSG_MOVE_N), 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)); + MenuEditItemBase::draw_edit_screen(GET_TEXT_F(MSG_MOVE_N), 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); } -#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 HAS_I_AXIS - void lcd_move_i() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_I), I_AXIS); } -#endif -#if HAS_J_AXIS - void lcd_move_j() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_J), J_AXIS); } -#endif -#if HAS_K_AXIS - void lcd_move_k() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_K), K_AXIS); } -#endif -#if HAS_U_AXIS - void lcd_move_u() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_U), U_AXIS); } -#endif -#if HAS_V_AXIS - void lcd_move_v() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_V), V_AXIS); } -#endif -#if HAS_W_AXIS - void lcd_move_w() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_W), W_AXIS); } -#endif + +// Move Z easy accessor +void lcd_move_z() { lcd_move_axis(Z_AXIS); } #if E_MANUAL @@ -132,10 +103,10 @@ void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } if (ui.should_draw()) { TERN_(MULTI_E_MANUAL, MenuItemBase::init(eindex)); MenuEditItemBase::draw_edit_screen( - GET_TEXT(TERN(MULTI_E_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), + GET_TEXT_F(TERN(MULTI_E_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), ftostr41sign(current_position.e PLUS_TERN0(IS_KINEMATIC, ui.manual_move.offset) - MINUS_TERN0(MANUAL_E_MOVES_RELATIVE, manual_move_e_origin) + MINUS_TERN0(MANUAL_E_MOVES_RELATIVE, ui.manual_move.e_origin) ) ); } // should_draw @@ -160,26 +131,22 @@ void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } #define FINE_MANUAL_MOVE 0.025 #endif -screenFunc_t _manual_move_func_ptr; - 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); + ui.goto_screen(ui.manual_move.screen_ptr); + thermalManager.set_menu_cold_override(true); } void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int8_t eindex=active_extruder) { - _manual_move_func_ptr = func; + ui.manual_move.screen_ptr = func; START_MENU(); if (LCD_HEIGHT >= 4) { - switch (axis) { - case X_AXIS: STATIC_ITEM(MSG_MOVE_X, SS_DEFAULT|SS_INVERT); break; - case Y_AXIS: STATIC_ITEM(MSG_MOVE_Y, SS_DEFAULT|SS_INVERT); break; - case Z_AXIS: STATIC_ITEM(MSG_MOVE_Z, SS_DEFAULT|SS_INVERT); break; - default: - TERN_(MANUAL_E_MOVES_RELATIVE, manual_move_e_origin = current_position.e); - STATIC_ITEM(MSG_MOVE_E, SS_DEFAULT|SS_INVERT); - break; + if (axis < NUM_AXES) + STATIC_ITEM_N(axis, MSG_MOVE_N, SS_DEFAULT|SS_INVERT); + else { + TERN_(MANUAL_E_MOVES_RELATIVE, ui.manual_move.e_origin = current_position.e); + STATIC_ITEM_N(eindex, MSG_MOVE_EN, SS_DEFAULT|SS_INVERT); } } @@ -195,22 +162,8 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int 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 - } + if (axis == Z_AXIS && (FINE_MANUAL_MOVE) > 0.0f && (FINE_MANUAL_MOVE) < 0.1f) + SUBMENU_f(F(STRINGIFY(FINE_MANUAL_MOVE)), MSG_MOVE_N_MM, []{ _goto_manual_move(float(FINE_MANUAL_MOVE)); }); } END_MENU(); } @@ -222,23 +175,20 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int } inline void _menu_move_distance_e_maybe() { - #if ENABLED(PREVENT_COLD_EXTRUSION) - const bool too_cold = thermalManager.tooColdToExtrude(active_extruder); - if (too_cold) { - ui.goto_screen([]{ - MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_PROCEED), GET_TEXT(MSG_BACK), - [] { _goto_menu_move_distance_e(); thermalManager.set_menu_cold_override(true); }, nullptr, - GET_TEXT(MSG_HOTEND_TOO_COLD), (const char *)nullptr, PSTR("!") - ); - }); - return; - } - #endif - _goto_menu_move_distance_e(); + if (thermalManager.tooColdToExtrude(active_extruder)) { + ui.goto_screen([]{ + MenuItem_confirm::select_screen( + GET_TEXT_F(MSG_BUTTON_PROCEED), GET_TEXT_F(MSG_BACK), + _goto_menu_move_distance_e, nullptr, + GET_TEXT_F(MSG_HOTEND_TOO_COLD), (const char *)nullptr, F("!") + ); + }); + } + else + _goto_menu_move_distance_e(); } -#endif // E_MANUAL +#endif void menu_move() { START_MENU(); @@ -248,85 +198,69 @@ void menu_move() { EDIT_ITEM(bool, MSG_LCD_SOFT_ENDSTOPS, &soft_endstop._enabled); #endif + // Move submenu for each axis 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_N(X_AXIS, MSG_MOVE_N, []{ _menu_move_distance(X_AXIS, []{ lcd_move_axis(X_AXIS); }); }); #if HAS_Y_AXIS - SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); + SUBMENU_N(Y_AXIS, MSG_MOVE_N, []{ _menu_move_distance(Y_AXIS, []{ lcd_move_axis(Y_AXIS); }); }); #endif } - #if ENABLED(DELTA) - else + else { + #if ENABLED(DELTA) ACTION_ITEM(MSG_FREE_XY, []{ line_to_z(delta_clip_start_height); ui.synchronize(); }); - #endif - + #endif + } #if HAS_Z_AXIS - SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); }); - #endif - #if HAS_I_AXIS - SUBMENU(MSG_MOVE_I, []{ _menu_move_distance(I_AXIS, lcd_move_i); }); - #endif - #if HAS_J_AXIS - SUBMENU(MSG_MOVE_J, []{ _menu_move_distance(J_AXIS, lcd_move_j); }); - #endif - #if HAS_K_AXIS - SUBMENU(MSG_MOVE_K, []{ _menu_move_distance(K_AXIS, lcd_move_k); }); - #endif - #if HAS_U_AXIS - SUBMENU(MSG_MOVE_U, []{ _menu_move_distance(U_AXIS, lcd_move_u); }); - #endif - #if HAS_V_AXIS - SUBMENU(MSG_MOVE_V, []{ _menu_move_distance(V_AXIS, lcd_move_v); }); - #endif - #if HAS_W_AXIS - SUBMENU(MSG_MOVE_W, []{ _menu_move_distance(W_AXIS, lcd_move_w); }); + #define _AXIS_MOVE(N) SUBMENU_N(N, MSG_MOVE_N, []{ _menu_move_distance(AxisEnum(N), []{ lcd_move_axis(AxisEnum(N)); }); }); + REPEAT_S(2, NUM_AXES, _AXIS_MOVE); #endif } else - GCODES_ITEM(MSG_AUTO_HOME, G28_STR); + GCODES_ITEM(MSG_AUTO_HOME, FPSTR(G28_STR)); #if ANY(SWITCHING_EXTRUDER, SWITCHING_NOZZLE, MAGNETIC_SWITCHING_TOOLHEAD) #if EXTRUDERS >= 4 switch (active_extruder) { - case 0: GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); break; - case 1: GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); break; - case 2: GCODES_ITEM_N(3, MSG_SELECT_E, PSTR("T3")); break; - case 3: GCODES_ITEM_N(2, MSG_SELECT_E, PSTR("T2")); break; + case 0: GCODES_ITEM_N(1, MSG_SELECT_E, F("T1")); break; + case 1: GCODES_ITEM_N(0, MSG_SELECT_E, F("T0")); break; + case 2: GCODES_ITEM_N(3, MSG_SELECT_E, F("T3")); break; + case 3: GCODES_ITEM_N(2, MSG_SELECT_E, F("T2")); break; #if EXTRUDERS == 6 - case 4: GCODES_ITEM_N(5, MSG_SELECT_E, PSTR("T5")); break; - case 5: GCODES_ITEM_N(4, MSG_SELECT_E, PSTR("T4")); break; + case 4: GCODES_ITEM_N(5, MSG_SELECT_E, F("T5")); break; + case 5: GCODES_ITEM_N(4, MSG_SELECT_E, F("T4")); break; #endif } #elif EXTRUDERS == 3 if (active_extruder < 2) { if (active_extruder) - GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); + GCODES_ITEM_N(0, MSG_SELECT_E, F("T0")); else - GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); + GCODES_ITEM_N(1, MSG_SELECT_E, F("T1")); } #else if (active_extruder) - GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); + GCODES_ITEM_N(0, MSG_SELECT_E, F("T0")); else - GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); + GCODES_ITEM_N(1, MSG_SELECT_E, F("T1")); #endif #elif ENABLED(DUAL_X_CARRIAGE) if (active_extruder) - GCODES_ITEM_N(0, MSG_SELECT_E, PSTR("T0")); + GCODES_ITEM_N(0, MSG_SELECT_E, F("T0")); else - GCODES_ITEM_N(1, MSG_SELECT_E, PSTR("T1")); + GCODES_ITEM_N(1, MSG_SELECT_E, F("T1")); #endif #if E_MANUAL // The current extruder - SUBMENU(MSG_MOVE_E, []{ _menu_move_distance_e_maybe(); }); + SUBMENU(MSG_MOVE_E, _menu_move_distance_e_maybe); - #define SUBMENU_MOVE_E(N) SUBMENU_N(N, MSG_MOVE_EN, []{ _menu_move_distance(E_AXIS, []{ lcd_move_e(MenuItemBase::itemIndex); }, MenuItemBase::itemIndex); }); + #define SUBMENU_MOVE_E(N) SUBMENU_N(N, MSG_MOVE_EN, []{ _menu_move_distance(E_AXIS, []{ lcd_move_e(N); }, N); }); #if EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE) @@ -337,8 +271,8 @@ void menu_move() { #elif MULTI_E_MANUAL - // Independent extruders with one E-stepper per hotend - LOOP_L_N(n, E_MANUAL) SUBMENU_MOVE_E(n); + // Independent extruders with one E stepper per hotend + REPEAT(E_MANUAL, SUBMENU_MOVE_E); #endif @@ -347,6 +281,8 @@ void menu_move() { END_MENU(); } +#define _HOME_ITEM(N) GCODES_ITEM_N(N##_AXIS, MSG_AUTO_HOME_A, F("G28" STR_##N)); + #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) // // "Motion" > "Homing" submenu @@ -355,32 +291,8 @@ void menu_move() { START_MENU(); BACK_ITEM(MSG_MOTION); - GCODES_ITEM(MSG_AUTO_HOME, G28_STR); - GCODES_ITEM_N(X_AXIS, MSG_AUTO_HOME_A, PSTR("G28X")); - #if HAS_Y_AXIS - GCODES_ITEM_N(Y_AXIS, MSG_AUTO_HOME_A, PSTR("G28Y")); - #endif - #if HAS_Z_AXIS - GCODES_ITEM_N(Z_AXIS, MSG_AUTO_HOME_A, PSTR("G28Z")); - #endif - #if HAS_I_AXIS - GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_I)); - #endif - #if HAS_J_AXIS - GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_J)); - #endif - #if HAS_K_AXIS - GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_K)); - #endif - #if HAS_U_AXIS - GCODES_ITEM_N(U_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_U)); - #endif - #if HAS_V_AXIS - GCODES_ITEM_N(V_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_V)); - #endif - #if HAS_W_AXIS - GCODES_ITEM_N(W_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_W)); - #endif + GCODES_ITEM(MSG_AUTO_HOME, FPSTR(G28_STR)); + MAIN_AXIS_MAP(_HOME_ITEM); END_MENU(); } @@ -416,33 +328,9 @@ void menu_motion() { #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) SUBMENU(MSG_HOMING, menu_home); #else - GCODES_ITEM(MSG_AUTO_HOME, G28_STR); + GCODES_ITEM(MSG_AUTO_HOME, FPSTR(G28_STR)); #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) - GCODES_ITEM_N(X_AXIS, MSG_AUTO_HOME_A, PSTR("G28X")); - #if HAS_Y_AXIS - GCODES_ITEM_N(Y_AXIS, MSG_AUTO_HOME_A, PSTR("G28Y")); - #endif - #if HAS_Z_AXIS - GCODES_ITEM_N(Z_AXIS, MSG_AUTO_HOME_A, PSTR("G28Z")); - #endif - #if HAS_I_AXIS - GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_I)); - #endif - #if HAS_J_AXIS - GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_J)); - #endif - #if HAS_K_AXIS - GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_K)); - #endif - #if HAS_U_AXIS - GCODES_ITEM_N(U_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_U)); - #endif - #if HAS_V_AXIS - GCODES_ITEM_N(V_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_V)); - #endif - #if HAS_W_AXIS - GCODES_ITEM_N(W_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_W)); - #endif + MAIN_AXIS_MAP(_HOME_ITEM); #endif #endif @@ -450,14 +338,22 @@ void menu_motion() { // Auto-calibration // #if ENABLED(CALIBRATION_GCODE) - GCODES_ITEM(MSG_AUTO_CALIBRATE, PSTR("G425")); + GCODES_ITEM(MSG_AUTO_CALIBRATE, F("G425")); #endif // // Auto Z-Align // #if EITHER(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) - GCODES_ITEM(MSG_AUTO_Z_ALIGN, PSTR("G34")); + GCODES_ITEM(MSG_AUTO_Z_ALIGN, F("G34")); + #endif + + // + // Probe Deploy/Stow + // + #if ENABLED(PROBE_DEPLOY_STOW_MENU) + GCODES_ITEM(MSG_MANUAL_DEPLOY, F("M401")); + GCODES_ITEM(MSG_MANUAL_STOW, F("M402")); #endif // @@ -482,7 +378,7 @@ void menu_motion() { #elif HAS_LEVELING && DISABLED(SLIM_LCD_MENUS) #if DISABLED(PROBE_MANUALLY) - GCODES_ITEM(MSG_LEVEL_BED, PSTR("G29N")); + GCODES_ITEM(MSG_LEVEL_BED, F("G29N")); #endif if (all_axes_homed() && leveling_is_valid()) { @@ -497,18 +393,18 @@ void menu_motion() { #endif - #if ENABLED(LEVEL_BED_CORNERS) && DISABLED(LCD_BED_LEVELING) + #if ENABLED(LCD_BED_TRAMMING) && DISABLED(LCD_BED_LEVELING) SUBMENU(MSG_BED_TRAMMING, _lcd_level_bed_corners); #endif #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) - GCODES_ITEM(MSG_M48_TEST, PSTR("G28O\nM48 P10")); + GCODES_ITEM(MSG_M48_TEST, F("G28O\nM48 P10")); #endif // // Disable Steppers // - GCODES_ITEM(MSG_DISABLE_STEPPERS, PSTR("M84")); + GCODES_ITEM(MSG_DISABLE_STEPPERS, F("M84")); END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_password.cpp b/Marlin/src/lcd/menu/menu_password.cpp index 32059103b3f4..d29b77311fd3 100644 --- a/Marlin/src/lcd/menu/menu_password.cpp +++ b/Marlin/src/lcd/menu/menu_password.cpp @@ -49,22 +49,22 @@ void Password::menu_password_entry() { 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_F(authenticating ? GET_TEXT_F(MSG_LOGIN_REQUIRED) : GET_TEXT_F(MSG_EDIT_PASSWORD), SS_CENTER|SS_INVERT); - STATIC_ITEM_P(NUL_STR, SS_CENTER, string); + STATIC_ITEM_F(FPSTR(NUL_STR), SS_CENTER, string); #if HAS_MARLINUI_U8GLIB - STATIC_ITEM_P(NUL_STR, SS_CENTER, ""); + STATIC_ITEM_F(FPSTR(NUL_STR), SS_CENTER, ""); #endif // Make the digit edit item look like a sub-menu - PGM_P const label = GET_TEXT(MSG_ENTER_DIGIT); - EDIT_ITEM_P(uint8, label, &editable.uint8, 0, 9, digit_entered); - MENU_ITEM_ADDON_START(utf8_strlen_P(label) + 1); - lcd_put_wchar(' '); - lcd_put_wchar('1' + digit_no); + FSTR_P const label = GET_TEXT_F(MSG_ENTER_DIGIT); + EDIT_ITEM_F(uint8, label, &editable.uint8, 0, 9, digit_entered); + MENU_ITEM_ADDON_START(utf8_strlen(label) + 1); + lcd_put_lchar(' '); + lcd_put_lchar('1' + digit_no); SETCURSOR_X(LCD_WIDTH - 2); - lcd_put_wchar('>'); + lcd_put_lchar('>'); MENU_ITEM_ADDON_END(); ACTION_ITEM(MSG_START_OVER, start_over); diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index 79db47005d0a..c7cbebaade82 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -62,27 +62,14 @@ void probe_offset_wizard_menu() { if (LCD_HEIGHT >= 4) STATIC_ITEM(MSG_MOVE_NOZZLE_TO_BED, SS_CENTER|SS_INVERT); - STATIC_ITEM_P(PSTR("Z"), SS_CENTER, ftostr42_52(current_position.z)); + STATIC_ITEM_F(F("Z"), SS_CENTER, ftostr42_52(current_position.z)); STATIC_ITEM(MSG_ZPROBE_ZOFFSET, SS_LEFT, ftostr42_52(calculated_z_offset)); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move_z( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move_z( 0.1f); }); - if ((FINE_MANUAL_MOVE) > 0.0f && (FINE_MANUAL_MOVE) < 0.1f) { - char tmp[20], numstr[10]; - // Determine digits needed right of decimal - const uint8_t digs = !UNEAR_ZERO((FINE_MANUAL_MOVE) * 1000 - int((FINE_MANUAL_MOVE) * 1000)) ? 4 : - !UNEAR_ZERO((FINE_MANUAL_MOVE) * 100 - int((FINE_MANUAL_MOVE) * 100)) ? 3 : 2; - sprintf_P(tmp, GET_TEXT(MSG_MOVE_N_MM), dtostrf(FINE_MANUAL_MOVE, 1, digs, numstr)); - #if DISABLED(HAS_GRAPHICAL_TFT) - SUBMENU_P(NUL_STR, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); - MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); - lcd_put_u8str(tmp); - MENU_ITEM_ADDON_END(); - #else - SUBMENU_P(tmp, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); - #endif - } + if ((FINE_MANUAL_MOVE) > 0.0f && (FINE_MANUAL_MOVE) < 0.1f) + SUBMENU_f(F(STRINGIFY(FINE_MANUAL_MOVE)), MSG_MOVE_N_MM, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); ACTION_ITEM(MSG_BUTTON_DONE, []{ set_offset_and_go_back(calculated_z_offset); @@ -107,7 +94,7 @@ void probe_offset_wizard_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.should_draw()) MenuItem_static::draw(1, GET_TEXT_F(MSG_PROBE_WIZARD_PROBING)); if (ui.wait_for_move) return; @@ -133,7 +120,7 @@ void prepare_for_probe_offset_wizard() { 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.synchronize(GET_TEXT_F(MSG_PROBE_WIZARD_MOVING)); ui.wait_for_move = false; SET_SOFT_ENDSTOP_LOOSE(true); // Disable soft endstops for free Z movement diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index 306d3d6c57df..bef86a6db8a9 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -33,7 +33,7 @@ #include "../../feature/spindle_laser.h" void menu_spindle_laser() { - bool is_enabled = cutter.enabled() && cutter.isReady; + bool is_enabled = cutter.enabled(); #if ENABLED(SPINDLE_CHANGE_DIR) bool is_rev = cutter.is_reverse(); #endif @@ -49,7 +49,13 @@ #endif editable.state = is_enabled; - EDIT_ITEM(bool, MSG_CUTTER(TOGGLE), &is_enabled, []{ if (editable.state) cutter.disable(); else cutter.enable_same_dir(); }); + EDIT_ITEM(bool, MSG_CUTTER(TOGGLE), &is_enabled, []{ + #if ENABLED(SPINDLE_FEATURE) + if (editable.state) cutter.disable(); else cutter.enable_same_dir(); + #else + cutter.laser_menu_toggle(!editable.state); + #endif + }); #if ENABLED(AIR_EVACUATION) bool evac_state = cutter.air_evac_state(); @@ -64,7 +70,7 @@ #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); }); + ACTION_ITEM_F(is_rev ? GET_TEXT_F(MSG_CUTTER(REVERSE)) : GET_TEXT_F(MSG_CUTTER(FORWARD)), []{ cutter.set_reverse(!editable.state); }); } #endif @@ -72,12 +78,10 @@ // 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); + #if ENABLED(HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY + EDIT_ITEM_FAST(CUTTER_MENU_FREQUENCY_TYPE, MSG_CUTTER_FREQUENCY, &cutter.frequency, 2000, 80000, cutter.refresh_frequency); + #endif #endif - - #if BOTH(MARLIN_DEV_MODE, HAL_CAN_SET_PWM_FREQ) && 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 fb539f006c14..e493972a9712 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -88,14 +88,14 @@ void Temperature::lcd_preheat(const uint8_t e, const int8_t indh, const int8_t i // Indexed "Preheat ABC" and "Heat Bed" items #define PREHEAT_ITEMS(M,E) do{ \ - ACTION_ITEM_N_S(E, ui.get_preheat_label(M), MSG_PREHEAT_M_H, []{ _preheat_both(M, MenuItemBase::itemIndex); }); \ - ACTION_ITEM_N_S(E, ui.get_preheat_label(M), MSG_PREHEAT_M_END_E, []{ _preheat_end(M, MenuItemBase::itemIndex); }); \ + ACTION_ITEM_N_f(E, ui.get_preheat_label(M), MSG_PREHEAT_M_H, []{ _preheat_both(M, MenuItemBase::itemIndex); }); \ + ACTION_ITEM_N_f(E, ui.get_preheat_label(M), MSG_PREHEAT_M_END_E, []{ _preheat_end(M, MenuItemBase::itemIndex); }); \ }while(0) #elif HAS_MULTI_HOTEND // No heated bed, so just indexed "Preheat ABC" items - #define PREHEAT_ITEMS(M,E) ACTION_ITEM_N_S(E, ui.get_preheat_label(M), MSG_PREHEAT_M_H, []{ _preheat_end(M, MenuItemBase::itemIndex); }) + #define PREHEAT_ITEMS(M,E) ACTION_ITEM_N_f(E, ui.get_preheat_label(M), MSG_PREHEAT_M_H, []{ _preheat_end(M, MenuItemBase::itemIndex); }) #endif @@ -112,16 +112,16 @@ void Temperature::lcd_preheat(const uint8_t e, const int8_t indh, const int8_t i #if HOTENDS == 1 #if HAS_HEATED_BED - ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M, []{ _preheat_both(editable.int8, 0); }); - ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M_END, do_preheat_end_m); + ACTION_ITEM_f(ui.get_preheat_label(m), MSG_PREHEAT_M, []{ _preheat_both(editable.int8, 0); }); + ACTION_ITEM_f(ui.get_preheat_label(m), MSG_PREHEAT_M_END, do_preheat_end_m); #else - ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M, do_preheat_end_m); + ACTION_ITEM_f(ui.get_preheat_label(m), MSG_PREHEAT_M, do_preheat_end_m); #endif #elif HAS_MULTI_HOTEND HOTEND_LOOP() PREHEAT_ITEMS(editable.int8, e); - ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M_ALL, []() { + ACTION_ITEM_f(ui.get_preheat_label(m), MSG_PREHEAT_M_ALL, []() { const celsius_t t = ui.material_preset[editable.int8].hotend_temp; HOTEND_LOOP() thermalManager.setTargetHotend(t, e); TERN(HAS_HEATED_BED, _preheat_bed(editable.int8), ui.return_to_status()); @@ -130,7 +130,7 @@ void Temperature::lcd_preheat(const uint8_t e, const int8_t indh, const int8_t i #endif #if HAS_HEATED_BED - ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M_BEDONLY, []{ _preheat_bed(editable.int8); }); + ACTION_ITEM_f(ui.get_preheat_label(m), MSG_PREHEAT_M_BEDONLY, []{ _preheat_bed(editable.int8); }); #endif END_MENU(); @@ -269,9 +269,9 @@ void menu_temperature() { LOOP_L_N(m, PREHEAT_COUNT) { editable.int8 = m; #if HAS_MULTI_HOTEND || HAS_HEATED_BED - SUBMENU_S(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); + SUBMENU_f(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); #elif HAS_HOTEND - ACTION_ITEM_S(ui.get_preheat_label(m), MSG_PREHEAT_M, do_preheat_end_m); + ACTION_ITEM_f(ui.get_preheat_label(m), MSG_PREHEAT_M, do_preheat_end_m); #endif } #endif @@ -296,9 +296,9 @@ void menu_temperature() { LOOP_L_N(m, PREHEAT_COUNT) { editable.int8 = m; #if HAS_MULTI_HOTEND || HAS_HEATED_BED - SUBMENU_S(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); + SUBMENU_f(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); + ACTION_ITEM_f(ui.get_preheat_label(m), MSG_PREHEAT_M, do_preheat_end_m); #endif } diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp index 995bc3b195ed..c3503ede41cd 100644 --- a/Marlin/src/lcd/menu/menu_tmc.cpp +++ b/Marlin/src/lcd/menu/menu_tmc.cpp @@ -32,7 +32,7 @@ #include "../../module/stepper/indirection.h" #include "../../feature/tmc_util.h" -#define TMC_EDIT_STORED_I_RMS(ST,STR) EDIT_ITEM_P(uint16_4, PSTR(STR), &stepper##ST.val_mA, 100, 3000, []{ stepper##ST.refresh_stepper_current(); }) +#define TMC_EDIT_STORED_I_RMS(ST,STR) EDIT_ITEM_F(uint16_4, F(STR), &stepper##ST.val_mA, 100, 3000, []{ stepper##ST.refresh_stepper_current(); }) void menu_tmc_current() { START_MENU(); @@ -90,7 +90,7 @@ void menu_tmc_current() { #if ENABLED(HYBRID_THRESHOLD) - #define TMC_EDIT_STORED_HYBRID_THRS(ST, STR) EDIT_ITEM_P(uint8, PSTR(STR), &stepper##ST.stored.hybrid_thrs, 0, 255, []{ stepper##ST.refresh_hybrid_thrs(); }); + #define TMC_EDIT_STORED_HYBRID_THRS(ST, STR) EDIT_ITEM_F(uint8, F(STR), &stepper##ST.stored.hybrid_thrs, 0, 255, []{ stepper##ST.refresh_hybrid_thrs(); }); void menu_tmc_hybrid_thrs() { START_MENU(); @@ -118,7 +118,7 @@ void menu_tmc_current() { #if ENABLED(SENSORLESS_HOMING) - #define TMC_EDIT_STORED_SGT(ST) EDIT_ITEM_P(int4, PSTR(STR_##ST), &stepper##ST.stored.homing_thrs, stepper##ST.sgt_min, stepper##ST.sgt_max, []{ stepper##ST.refresh_homing_thrs(); }); + #define TMC_EDIT_STORED_SGT(ST) EDIT_ITEM_F(int4, F(STR_##ST), &stepper##ST.stored.homing_thrs, stepper##ST.sgt_min, stepper##ST.sgt_max, []{ stepper##ST.refresh_homing_thrs(); }); void menu_tmc_homing_thrs() { START_MENU(); @@ -144,7 +144,7 @@ void menu_tmc_current() { #if HAS_STEALTHCHOP - #define TMC_EDIT_STEP_MODE(ST, STR) EDIT_ITEM_P(bool, PSTR(STR), &stepper##ST.stored.stealthChop_enabled, []{ stepper##ST.refresh_stepping_mode(); }) + #define TMC_EDIT_STEP_MODE(ST, STR) EDIT_ITEM_F(bool, F(STR), &stepper##ST.stored.stealthChop_enabled, []{ stepper##ST.refresh_stepping_mode(); }) void menu_tmc_step_mode() { START_MENU(); diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index 0789044d7d8e..1dd8a1cab6fd 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -83,7 +83,7 @@ static void tramming_wizard_menu() { // Draw a menu item for each tramming point for (tram_index = 0; tram_index < G35_PROBE_COUNT; tram_index++) - SUBMENU_P((PGM_P)pgm_read_ptr(&tramming_point_name[tram_index]), _menu_single_probe); + SUBMENU_F(FPSTR(pgm_read_ptr(&tramming_point_name[tram_index])), _menu_single_probe); ACTION_ITEM(MSG_BUTTON_DONE, []{ probe.stow(); // Stow before exiting Tramming Wizard diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 7954edf5a127..bc5200196717 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -50,7 +50,9 @@ #include "../dogm/marlinui_DOGM.h" #endif - void _lcd_babystep(const AxisEnum axis, PGM_P const msg) { + // TODO: Replace fmsg with MSG_BABYSTEP_N and index substitution + + void _lcd_babystep(const AxisEnum axis, FSTR_P const fmsg) { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); if (ui.encoderPosition) { const int16_t steps = int16_t(ui.encoderPosition) * ( @@ -66,7 +68,7 @@ } if (ui.should_draw()) { const float mps = planner.mm_per_step[axis]; - MenuEditItemBase::draw_edit_screen(msg, BABYSTEP_TO_STR(mps * babystep.accum)); + MenuEditItemBase::draw_edit_screen(fmsg, BABYSTEP_TO_STR(mps * babystep.accum)); #if ENABLED(BABYSTEP_DISPLAY_TOTAL) const bool in_view = TERN1(HAS_MARLINUI_U8GLIB, PAGE_CONTAINS(LCD_PIXEL_HEIGHT - MENU_FONT_HEIGHT, LCD_PIXEL_HEIGHT - 1)); if (in_view) { @@ -74,12 +76,12 @@ #if ENABLED(TFT_COLOR_UI) lcd_moveto(4, 3); lcd_put_u8str(GET_TEXT_F(MSG_BABYSTEP_TOTAL)); - lcd_put_wchar(':'); + lcd_put_lchar(':'); lcd_moveto(10, 3); #else lcd_moveto(0, TERN(HAS_MARLINUI_U8GLIB, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT, LCD_HEIGHT - 1)); lcd_put_u8str(GET_TEXT_F(MSG_BABYSTEP_TOTAL)); - lcd_put_wchar(':'); + lcd_put_lchar(':'); #endif lcd_put_u8str(BABYSTEP_TO_STR(mps * babystep.axis_total[BS_TOTAL_IND(axis)])); } @@ -94,12 +96,12 @@ } #if ENABLED(BABYSTEP_XY) - void _lcd_babystep_x() { _lcd_babystep(X_AXIS, GET_TEXT(MSG_BABYSTEP_X)); } - void _lcd_babystep_y() { _lcd_babystep(Y_AXIS, GET_TEXT(MSG_BABYSTEP_Y)); } + void _lcd_babystep_x() { _lcd_babystep(X_AXIS, GET_TEXT_F(MSG_BABYSTEP_X)); } + void _lcd_babystep_y() { _lcd_babystep(Y_AXIS, GET_TEXT_F(MSG_BABYSTEP_Y)); } #endif #if DISABLED(BABYSTEP_ZPROBE_OFFSET) - void _lcd_babystep_z() { _lcd_babystep(Z_AXIS, GET_TEXT(MSG_BABYSTEP_Z)); } + void _lcd_babystep_z() { _lcd_babystep(Z_AXIS, GET_TEXT_F(MSG_BABYSTEP_Z)); } void lcd_babystep_z() { _lcd_babystep_go(_lcd_babystep_z); } #endif @@ -118,7 +120,7 @@ void menu_tune() { // Manual bed leveling, Bed Z: // #if BOTH(MESH_BED_LEVELING, LCD_BED_LEVELING) - EDIT_ITEM(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); + EDIT_ITEM(float43, MSG_BED_Z, &bedlevel.z_offset, -1, 1); #endif // @@ -223,13 +225,13 @@ void menu_tune() { // #if ENABLED(BABYSTEPPING) #if ENABLED(BABYSTEP_XY) - SUBMENU(MSG_BABYSTEP_X, []{ _lcd_babystep_go(_lcd_babystep_x); }); - SUBMENU(MSG_BABYSTEP_Y, []{ _lcd_babystep_go(_lcd_babystep_y); }); + SUBMENU_N(X_AXIS, MSG_BABYSTEP_N, []{ _lcd_babystep_go(_lcd_babystep_x); }); + SUBMENU_N(Y_AXIS, MSG_BABYSTEP_N, []{ _lcd_babystep_go(_lcd_babystep_y); }); #endif #if ENABLED(BABYSTEP_ZPROBE_OFFSET) SUBMENU(MSG_ZPROBE_ZOFFSET, lcd_babystep_zoffset); #else - SUBMENU(MSG_BABYSTEP_Z, lcd_babystep_z); + SUBMENU_N(Z_AXIS, MSG_BABYSTEP_N, lcd_babystep_z); #endif #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index d324e057be62..62c1770bd4c3 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -58,7 +58,7 @@ inline float rounded_mesh_value() { /** * 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 + * movement. While this screen is active bedlevel.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. * @@ -67,39 +67,39 @@ inline float rounded_mesh_value() { * - Draw the graphical overlay, if enabled. * - Update the 'refresh' state according to the display type */ -void _lcd_mesh_fine_tune(PGM_P const msg) { +void _lcd_mesh_fine_tune(FSTR_P const fmsg) { constexpr float mesh_edit_step = 1.0f / 200.0f; ui.defer_status_screen(); - if (ubl.encoder_diff) { + if (bedlevel.encoder_diff) { mesh_edit_accumulator += TERN(IS_TFTGLCD_PANEL, - ubl.encoder_diff * mesh_edit_step / ENCODER_PULSES_PER_STEP, - ubl.encoder_diff > 0 ? mesh_edit_step : -mesh_edit_step + bedlevel.encoder_diff * mesh_edit_step / ENCODER_PULSES_PER_STEP, + bedlevel.encoder_diff > 0 ? mesh_edit_step : -mesh_edit_step ); - ubl.encoder_diff = 0; + bedlevel.encoder_diff = 0; IF_DISABLED(IS_TFTGLCD_PANEL, ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); } TERN_(IS_TFTGLCD_PANEL, ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); if (ui.should_draw()) { const float rounded_f = rounded_mesh_value(); - MenuEditItemBase::draw_edit_screen(msg, ftostr43sign(rounded_f)); + MenuEditItemBase::draw_edit_screen(fmsg, ftostr43sign(rounded_f)); TERN_(MESH_EDIT_GFX_OVERLAY, ui.zoffset_overlay(rounded_f)); TERN_(HAS_GRAPHICAL_TFT, ui.refresh(LCDVIEW_NONE)); } } // -// Init mesh editing and go to the fine tuning screen (ubl.fine_tune_mesh) +// Init mesh editing and go to the fine tuning screen (bedlevel.fine_tune_mesh) // To capture encoder events UBL will also call ui.capture and ui.release. // void MarlinUI::ubl_mesh_edit_start(const_float_t initial) { TERN_(HAS_GRAPHICAL_TFT, clear_lcd()); mesh_edit_accumulator = initial; - goto_screen([]{ _lcd_mesh_fine_tune(GET_TEXT(MSG_MESH_EDIT_Z)); }); + goto_screen([]{ _lcd_mesh_fine_tune(GET_TEXT_F(MSG_MESH_EDIT_Z)); }); } // -// Get the mesh value within a Z adjustment loop (ubl.fine_tune_mesh) +// Get the mesh value within a Z adjustment loop (bedlevel.fine_tune_mesh) // float MarlinUI::ubl_mesh_value() { return rounded_mesh_value(); } @@ -176,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("G29P4RT")); - GCODES_ITEM(MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29P4T")); + GCODES_ITEM(MSG_UBL_FINE_TUNE_ALL, F("G29P4RT")); + GCODES_ITEM(MSG_UBL_FINE_TUNE_CLOSEST, F("G29P4T")); SUBMENU(MSG_UBL_MESH_HEIGHT_ADJUST, _menu_ubl_height_adjust); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); END_MENU(); @@ -211,10 +211,10 @@ void _lcd_ubl_edit_mesh() { #if HAS_PREHEAT #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\nG26CPI" STRINGIFY(M))); + GCODES_ITEM_N_f(M, ui.get_preheat_label(M), MSG_UBL_VALIDATE_MESH_M, F("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\nG26CPB0I" STRINGIFY(M))); + GCODES_ITEM_N_f(M, ui.get_preheat_label(M), MSG_UBL_VALIDATE_MESH_M, F("G28\nG26CPB0I" STRINGIFY(M))); #endif REPEAT(PREHEAT_COUNT, VALIDATE_MESH_GCODE_ITEM) #endif @@ -255,7 +255,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("G29J0")); + GCODES_ITEM(MSG_UBL_3POINT_MESH_LEVELING, F("G29J0")); SUBMENU(MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); END_MENU(); @@ -284,14 +284,14 @@ 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("G29P3T0")); - GCODES_ITEM(MSG_UBL_MANUAL_FILLIN, PSTR("G29P2BT0")); + GCODES_ITEM(MSG_UBL_SMART_FILLIN, F("G29P3T0")); + GCODES_ITEM(MSG_UBL_MANUAL_FILLIN, F("G29P2BT0")); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); END_MENU(); } void _lcd_ubl_invalidate() { - ubl.invalidate(); + bedlevel.invalidate(); SERIAL_ECHOLNPGM("Mesh invalidated."); } @@ -317,8 +317,8 @@ void _lcd_ubl_build_mesh() { #else #define PREHEAT_BED_GCODE(M) "" #endif - #define BUILD_MESH_GCODE_ITEM(M) GCODES_ITEM_S(ui.get_preheat_label(M), MSG_UBL_BUILD_MESH_M, \ - PSTR( \ + #define BUILD_MESH_GCODE_ITEM(M) GCODES_ITEM_f(ui.get_preheat_label(M), MSG_UBL_BUILD_MESH_M, \ + F( \ "G28\n" \ PREHEAT_BED_GCODE(M) \ "M109I" STRINGIFY(M) "\n" \ @@ -342,11 +342,11 @@ void _lcd_ubl_build_mesh() { #endif // HAS_PREHEAT SUBMENU(MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_custom_mesh); - GCODES_ITEM(MSG_UBL_BUILD_COLD_MESH, PSTR("G29NP1")); + GCODES_ITEM(MSG_UBL_BUILD_COLD_MESH, F("G29NP1")); SUBMENU(MSG_UBL_FILLIN_MESH, _menu_ubl_fillin); - GCODES_ITEM(MSG_UBL_CONTINUE_MESH, PSTR("G29P1C")); + GCODES_ITEM(MSG_UBL_CONTINUE_MESH, F("G29P1C")); ACTION_ITEM(MSG_UBL_INVALIDATE_ALL, _lcd_ubl_invalidate); - GCODES_ITEM(MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29I")); + GCODES_ITEM(MSG_UBL_INVALIDATE_CLOSEST, F("G29I")); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); END_MENU(); } @@ -354,14 +354,14 @@ void _lcd_ubl_build_mesh() { /** * UBL Load / Save Mesh Commands */ -inline void _lcd_ubl_load_save_cmd(const char loadsave, PGM_P const msg) { +inline void _lcd_ubl_load_save_cmd(const char loadsave, FSTR_P const fmsg) { char ubl_lcd_gcode[40]; 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); + sprintf_P(&ubl_lcd_gcode[strlen(ubl_lcd_gcode)], FTOP(fmsg), ubl_storage_slot); gcode.process_subcommands_now(ubl_lcd_gcode); } -void _lcd_ubl_load_mesh_cmd() { _lcd_ubl_load_save_cmd('L', GET_TEXT(MSG_MESH_LOADED)); } -void _lcd_ubl_save_mesh_cmd() { _lcd_ubl_load_save_cmd('S', GET_TEXT(MSG_MESH_SAVED)); } +void _lcd_ubl_load_mesh_cmd() { _lcd_ubl_load_save_cmd('L', GET_TEXT_F(MSG_MESH_LOADED)); } +void _lcd_ubl_save_mesh_cmd() { _lcd_ubl_load_save_cmd('S', GET_TEXT_F(MSG_MESH_SAVED)); } /** * UBL Mesh Storage submenu @@ -390,8 +390,8 @@ void _lcd_ubl_storage_mesh() { */ 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); + dtostrf(bedlevel.get_mesh_x(x_plot), 0, 2, str); + dtostrf(bedlevel.get_mesh_y(y_plot), 0, 2, str2); 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); } @@ -400,7 +400,7 @@ 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) }; + const xy_pos_t xy = { bedlevel.get_mesh_x(x_plot), bedlevel.get_mesh_y(y_plot) }; // Some printers have unreachable areas in the mesh. Skip the move if unreachable. if (!position_is_reachable(xy)) return; @@ -459,7 +459,7 @@ void ubl_map_screen() { // Validate if needed #if IS_KINEMATIC - const xy_pos_t xy = { ubl.mesh_index_to_xpos(x), ubl.mesh_index_to_ypos(y) }; + const xy_pos_t xy = { bedlevel.get_mesh_x(x), bedlevel.get_mesh_y(y) }; if (position_is_reachable(xy)) break; // Found a valid point ui.encoderPosition += step_dir; // Test the next point #endif @@ -500,7 +500,7 @@ void _ubl_map_screen_homing() { ui.defer_status_screen(); _lcd_draw_homing(); if (all_axes_homed()) { - ubl.lcd_map_control = true; // Return to the map screen after editing Z + bedlevel.lcd_map_control = true; // Return to the map screen after editing Z ui.goto_screen(ubl_map_screen, grid_index(x_plot, y_plot)); // Pre-set the encoder value ui.manual_move.menu_scale = 0; // Immediate move ubl_map_move_to_xy(); // Move to current mesh point @@ -531,9 +531,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("G29T0")); - GCODES_ITEM(MSG_UBL_OUTPUT_MAP_CSV, PSTR("G29T1")); - GCODES_ITEM(MSG_UBL_OUTPUT_MAP_BACKUP, PSTR("G29S-1")); + GCODES_ITEM(MSG_UBL_OUTPUT_MAP_HOST, F("G29T0")); + GCODES_ITEM(MSG_UBL_OUTPUT_MAP_CSV, F("G29T1")); + GCODES_ITEM(MSG_UBL_OUTPUT_MAP_BACKUP, F("G29S-1")); END_MENU(); } @@ -550,7 +550,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("G29I999\nG29P2BT0")); + GCODES_ITEM(MSG_UBL_MANUAL_MESH, F("G29I999\nG29P2BT0")); #if ENABLED(G26_MESH_VALIDATION) SUBMENU(MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); #endif @@ -576,12 +576,12 @@ 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("G29NP1")); - GCODES_ITEM(MSG_UBL_2_SMART_FILLIN, PSTR("G29P3T0")); + GCODES_ITEM(MSG_UBL_1_BUILD_COLD_MESH, F("G29NP1")); + GCODES_ITEM(MSG_UBL_2_SMART_FILLIN, F("G29P3T0")); SUBMENU(MSG_UBL_3_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - GCODES_ITEM(MSG_UBL_4_FINE_TUNE_ALL, PSTR("G29P4RT")); + GCODES_ITEM(MSG_UBL_4_FINE_TUNE_ALL, F("G29P4RT")); SUBMENU(MSG_UBL_5_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - GCODES_ITEM(MSG_UBL_6_FINE_TUNE_ALL, PSTR("G29P4RT")); + GCODES_ITEM(MSG_UBL_6_FINE_TUNE_ALL, F("G29P4RT")); ACTION_ITEM(MSG_UBL_7_SAVE_MESH, _lcd_ubl_save_mesh_cmd); END_MENU(); } @@ -650,9 +650,9 @@ void _lcd_ubl_level_bed() { START_MENU(); BACK_ITEM(MSG_MOTION); if (planner.leveling_active) - GCODES_ITEM(MSG_UBL_DEACTIVATE_MESH, PSTR("G29D")); + GCODES_ITEM(MSG_UBL_DEACTIVATE_MESH, F("G29D")); else - GCODES_ITEM(MSG_UBL_ACTIVATE_MESH, PSTR("G29A")); + GCODES_ITEM(MSG_UBL_ACTIVATE_MESH, F("G29A")); #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); }); @@ -667,7 +667,7 @@ void _lcd_ubl_level_bed() { 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("G29W")); + GCODES_ITEM(MSG_UBL_INFO_UBL, F("G29W")); END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_x_twist.cpp b/Marlin/src/lcd/menu/menu_x_twist.cpp index ce46053dfc34..a069b427c6bf 100644 --- a/Marlin/src/lcd/menu/menu_x_twist.cpp +++ b/Marlin/src/lcd/menu/menu_x_twist.cpp @@ -51,7 +51,7 @@ void xatc_wizard_done() { ui.goto_screen(menu_advanced_settings); } if (ui.should_draw()) - MenuItem_static::draw(LCD_HEIGHT >= 4, GET_TEXT(MSG_XATC_DONE)); + MenuItem_static::draw(LCD_HEIGHT >= 4, GET_TEXT_F(MSG_XATC_DONE)); ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); } @@ -62,14 +62,14 @@ void xatc_wizard_goto_next_point(); // void xatc_wizard_update_z_offset() { MenuItem_confirm::select_screen( - GET_TEXT(MSG_YES), GET_TEXT(MSG_NO) + GET_TEXT_F(MSG_YES), GET_TEXT_F(MSG_NO) , []{ probe.offset.z = z_offset; ui.goto_screen(xatc_wizard_done); } , xatc_wizard_done - , GET_TEXT(MSG_XATC_UPDATE_Z_OFFSET) - , ftostr42_52(z_offset), PSTR("?") + , GET_TEXT_F(MSG_XATC_UPDATE_Z_OFFSET) + , ftostr42_52(z_offset), F("?") ); } @@ -93,27 +93,14 @@ void xatc_wizard_menu() { if (LCD_HEIGHT >= 4) STATIC_ITEM(MSG_MOVE_NOZZLE_TO_BED, SS_CENTER|SS_INVERT); - STATIC_ITEM_P(PSTR("Z="), SS_CENTER, ftostr42_52(current_position.z)); + STATIC_ITEM_F(F("Z="), SS_CENTER, ftostr42_52(current_position.z)); STATIC_ITEM(MSG_ZPROBE_ZOFFSET, SS_LEFT, ftostr42_52(calculated_z_offset)); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move_z( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move_z( 0.1f); }); - if ((FINE_MANUAL_MOVE) > 0.0f && (FINE_MANUAL_MOVE) < 0.1f) { - char tmp[20], numstr[10]; - // Determine digits needed right of decimal - const uint8_t digs = !UNEAR_ZERO((FINE_MANUAL_MOVE) * 1000 - int((FINE_MANUAL_MOVE) * 1000)) ? 4 : - !UNEAR_ZERO((FINE_MANUAL_MOVE) * 100 - int((FINE_MANUAL_MOVE) * 100)) ? 3 : 2; - sprintf_P(tmp, GET_TEXT(MSG_MOVE_N_MM), dtostrf(FINE_MANUAL_MOVE, 1, digs, numstr)); - #if DISABLED(HAS_GRAPHICAL_TFT) - SUBMENU_P(NUL_STR, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); - MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); - lcd_put_u8str(tmp); - MENU_ITEM_ADDON_END(); - #else - SUBMENU_P(tmp, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); - #endif - } + if ((FINE_MANUAL_MOVE) > 0.0f && (FINE_MANUAL_MOVE) < 0.1f) + SUBMENU_f(F(STRINGIFY(FINE_MANUAL_MOVE)), MSG_MOVE_N_MM, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); ACTION_ITEM(MSG_BUTTON_DONE, xatc_wizard_set_offset_and_go_to_next_point); @@ -127,7 +114,7 @@ void xatc_wizard_moving() { if (ui.should_draw()) { char msg[10]; sprintf_P(msg, PSTR("%i / %u"), manual_probe_index + 1, XATC_MAX_POINTS); - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_LEVEL_BED_NEXT_POINT), msg); + MenuEditItemBase::draw_edit_screen(GET_TEXT_F(MSG_LEVEL_BED_NEXT_POINT), msg); } ui.refresh(LCDVIEW_CALL_NO_REDRAW); if (!ui.wait_for_move) ui.goto_screen(xatc_wizard_menu); @@ -180,7 +167,7 @@ void xatc_wizard_goto_next_point() { // void xatc_wizard_homing_done() { if (ui.should_draw()) { - MenuItem_static::draw(1, GET_TEXT(MSG_LEVEL_BED_WAITING)); + MenuItem_static::draw(1, GET_TEXT_F(MSG_LEVEL_BED_WAITING)); // Color UI needs a control to detect a touch #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) diff --git a/Marlin/src/lcd/tft/tft.h b/Marlin/src/lcd/tft/tft.h index 435e7c30bf51..67cec2ee1c7e 100644 --- a/Marlin/src/lcd/tft/tft.h +++ b/Marlin/src/lcd/tft/tft.h @@ -94,7 +94,7 @@ class TFT { static void canvas(uint16_t x, uint16_t y, uint16_t width, uint16_t height) { queue.canvas(x, y, width, height); } static void set_background(uint16_t color) { queue.set_background(color); } static void add_text(uint16_t x, uint16_t y, uint16_t color, TFT_String tft_string, uint16_t maxWidth = 0) { queue.add_text(x, y, color, tft_string.string(), maxWidth); } - static void add_text(uint16_t x, uint16_t y, uint16_t color, const char *string, uint16_t maxWidth = 0) { queue.add_text(x, y, color, (uint8_t *)string, maxWidth); } + static void add_text(uint16_t x, uint16_t y, uint16_t color, const char *string, uint16_t maxWidth = 0) { queue.add_text(x, y, color, string, maxWidth); } static void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) { queue.add_image(x, y, image, colors); } static void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t color_main = COLOR_WHITE, uint16_t color_background = COLOR_BACKGROUND, uint16_t color_shadow = COLOR_BLACK) { queue.add_image(x, y, image, color_main, color_background, color_shadow); } static void add_bar(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.add_bar(x, y, width, height, color); } diff --git a/Marlin/src/lcd/tft/tft_queue.cpp b/Marlin/src/lcd/tft/tft_queue.cpp index 3f604005f9e5..25ab452cef31 100644 --- a/Marlin/src/lcd/tft/tft_queue.cpp +++ b/Marlin/src/lcd/tft/tft_queue.cpp @@ -215,13 +215,13 @@ void TFT_Queue::handle_queue_overflow(uint16_t sizeNeeded) { } } -void TFT_Queue::add_text(uint16_t x, uint16_t y, uint16_t color, uint8_t *string, uint16_t maxWidth) { +void TFT_Queue::add_text(uint16_t x, uint16_t y, uint16_t color, const 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; + const uint8_t *pointer = string; parameters->type = CANVAS_ADD_TEXT; parameters->x = x; diff --git a/Marlin/src/lcd/tft/tft_queue.h b/Marlin/src/lcd/tft/tft_queue.h index 51387254c55d..55d0a526b5e3 100644 --- a/Marlin/src/lcd/tft/tft_queue.h +++ b/Marlin/src/lcd/tft/tft_queue.h @@ -139,7 +139,10 @@ class TFT_Queue { 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); static void set_background(uint16_t color); - static void add_text(uint16_t x, uint16_t y, uint16_t color, uint8_t *string, uint16_t maxWidth); + static void add_text(uint16_t x, uint16_t y, uint16_t color, const uint8_t *string, uint16_t maxWidth); + static void add_text(uint16_t x, uint16_t y, uint16_t color, const char *string, uint16_t maxWidth) { + add_text(x, y, color, (uint8_t *)string, maxWidth); + } static void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t *colors); static void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t color_main, uint16_t color_background, uint16_t color_shadow); diff --git a/Marlin/src/lcd/tft/tft_string.cpp b/Marlin/src/lcd/tft/tft_string.cpp index 008b5eba35cf..d589b0465b7f 100644 --- a/Marlin/src/lcd/tft/tft_string.cpp +++ b/Marlin/src/lcd/tft/tft_string.cpp @@ -35,7 +35,7 @@ glyph_t *TFT_String::glyphs[256]; font_t *TFT_String::font_header; -uint8_t TFT_String::data[]; +char TFT_String::data[]; uint16_t TFT_String::span; uint8_t TFT_String::length; @@ -84,24 +84,22 @@ void TFT_String::set() { length = 0; } -uint8_t read_byte(uint8_t *byte) { return *byte; } - /** * Add a string, applying substitutions for the following characters: * - * $ displays an inserted C-string given by the itemString parameter + * $ displays the string given by fstr or cstr * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder */ -void TFT_String::add(uint8_t *string, int8_t index, uint8_t *itemString/*=nullptr*/) { - wchar_t wchar; +void TFT_String::add(const char *tpl, const int8_t index, const char *cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/) { + lchar_t wc; - while (*string) { - string = get_utf8_value_cb(string, read_byte, &wchar); - if (wchar > 255) wchar |= 0x0080; - uint8_t ch = uint8_t(wchar & 0x00FF); + while (*tpl) { + tpl = get_utf8_value_cb(tpl, read_byte_ram, wc); + if (wc > 255) wc |= 0x0080; + const uint8_t ch = uint8_t(wc & 0x00FF); if (ch == '=' || ch == '~' || ch == '*') { if (index >= 0) { @@ -111,10 +109,12 @@ void TFT_String::add(uint8_t *string, int8_t index, uint8_t *itemString/*=nullpt add_character('0' + inum); } else - add(index == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED)); + add(index == -2 ? GET_TEXT_F(MSG_CHAMBER) : GET_TEXT_F(MSG_BED)); } - else if (ch == '$' && itemString) - add(itemString); + else if (ch == '$' && fstr) + add(fstr); + else if (ch == '$' && cstr) + add(cstr); else if (ch == '@') add_character(AXIS_CHAR(index)); else @@ -123,19 +123,19 @@ void TFT_String::add(uint8_t *string, int8_t index, uint8_t *itemString/*=nullpt eol(); } -void TFT_String::add(uint8_t *string, uint8_t max_len) { - wchar_t wchar; - 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); +void TFT_String::add(const char *cstr, uint8_t max_len/*=MAX_STRING_LENGTH*/) { + lchar_t wc; + while (*cstr && max_len) { + cstr = get_utf8_value_cb(cstr, read_byte_ram, wc); + if (wc > 255) wc |= 0x0080; + const uint8_t ch = uint8_t(wc & 0x00FF); add_character(ch); max_len--; } eol(); } -void TFT_String::add_character(uint8_t character) { +void TFT_String::add_character(const char character) { if (length < MAX_STRING_LENGTH) { data[length] = character; length++; @@ -143,7 +143,7 @@ void TFT_String::add_character(uint8_t character) { } } -void TFT_String::rtrim(uint8_t character) { +void TFT_String::rtrim(const char character) { while (length) { if (data[length - 1] == 0x20 || data[length - 1] == character) { length--; @@ -155,7 +155,7 @@ void TFT_String::rtrim(uint8_t character) { } } -void TFT_String::ltrim(uint8_t character) { +void TFT_String::ltrim(const char character) { uint16_t i, j; for (i = 0; (i < length) && (data[i] == 0x20 || data[i] == character); i++) { span -= glyph(data[i])->DWidth; @@ -166,7 +166,7 @@ void TFT_String::ltrim(uint8_t character) { eol(); } -void TFT_String::trim(uint8_t character) { +void TFT_String::trim(const char character) { rtrim(character); ltrim(character); } diff --git a/Marlin/src/lcd/tft/tft_string.h b/Marlin/src/lcd/tft/tft_string.h index e486c2ee91c8..d43e0b0df2b4 100644 --- a/Marlin/src/lcd/tft/tft_string.h +++ b/Marlin/src/lcd/tft/tft_string.h @@ -21,8 +21,12 @@ */ #pragma once +// TODO: Make AVR-compatible with separate ROM / RAM string methods + #include +#include "../fontutils.h" + extern const uint8_t ISO10646_1_5x7[]; extern const uint8_t font10x20[]; @@ -67,14 +71,15 @@ class TFT_String { static glyph_t *glyphs[256]; static font_t *font_header; - static uint8_t data[MAX_STRING_LENGTH + 1]; + static char data[MAX_STRING_LENGTH + 1]; static uint16_t span; // in pixels - static uint8_t length; // in characters - static void add_character(uint8_t character); - static void eol() { data[length] = 0x00; } + static void add_character(const char character); + static void eol() { data[length] = '\0'; } public: + static uint8_t length; // in characters + static void set_font(const uint8_t *font); static void add_glyphs(const uint8_t *font); @@ -83,25 +88,69 @@ class TFT_String { static glyph_t *glyph(uint8_t character) { return glyphs[character] ?: glyphs[0x3F]; } /* Use '?' for unknown glyphs */ static glyph_t *glyph(uint8_t *character) { return glyph(*character); } + /** + * @brief Set the string empty + */ static void set(); - static void add(uint8_t character) { add_character(character); eol(); } - 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=nullptr) { set(); add(string, index, (uint8_t *)itemString); }; - static void set(const char *string) { set((uint8_t *)string); } - static void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } - static void add(const char *string) { add((uint8_t *)string); } - - static void trim(uint8_t character=0x20); - static void rtrim(uint8_t character=0x20); - static void ltrim(uint8_t character=0x20); - - static void truncate(uint8_t maxlen) { if (length > maxlen) { length = maxlen; eol(); } } + /** + * @brief Append an ASCII character and EOL + * + * @param character The ASCII character + */ + static void add(const char character) { add_character(character); eol(); } + static void set(const lchar_t &character) { set(); add(character); } + + /** + * @brief Append / Set C-string + * + * @param cstr The string + * @param max_len Character limit + */ + static void add(const char *cstr, uint8_t max_len=MAX_STRING_LENGTH); + static void set(const char *cstr, uint8_t max_len=MAX_STRING_LENGTH) { set(); add(cstr, max_len); } + + /** + * @brief Append / Set F-string + * + * @param fstr The string + * @param max_len Character limit + */ + static void add(FSTR_P const fstr, uint8_t max_len=MAX_STRING_LENGTH) { add(FTOP(fstr), max_len); } + static void set(FSTR_P const fstr, uint8_t max_len=MAX_STRING_LENGTH) { set(FTOP(fstr), max_len); } + + /** + * @brief Append / Set C-string with optional substitution + * + * @param tpl A string with optional substitution + * @param index An index + * @param cstr An SRAM C-string to use for $ substitution + * @param fstr A ROM F-string to use for $ substitution + */ + static void add(const char *tpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr); + static void set(const char *tpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { set(); add(tpl, index, cstr, fstr); } + + /** + * @brief Append / Set F-string with optional substitution + * + * @param ftpl A ROM F-string with optional substitution + * @param index An index + * @param cstr An SRAM C-string to use for $ substitution + * @param fstr A ROM F-string to use for $ substitution + */ + static void add(FSTR_P const ftpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { add(FTOP(ftpl), index, cstr, fstr); } + static void set(FSTR_P const ftpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { set(); add(ftpl, index, cstr, fstr); } + + // Common string ops + static void trim(const char character=' '); + static void rtrim(const char character=' '); + static void ltrim(const char character=' '); + static void truncate(const uint8_t maxlen) { if (length > maxlen) { length = maxlen; eol(); } } + + // Accessors + static char *string() { return data; } 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; } + static uint16_t center(const uint16_t width) { return span > width ? 0 : (width - span) / 2; } }; extern TFT_String tft_string; diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index a04715a2952d..050b59f39f90 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -175,13 +175,13 @@ void Touch::touch(touch_control_t *control) { ui.refresh(); break; case PAGE_DOWN: - encoderTopLine = encoderTopLine + 2 * LCD_HEIGHT < screen_items ? encoderTopLine + LCD_HEIGHT : screen_items - LCD_HEIGHT; + encoderTopLine = (encoderTopLine + 2 * LCD_HEIGHT < screen_items) ? encoderTopLine + LCD_HEIGHT : screen_items - LCD_HEIGHT; ui.encoderPosition = ui.encoderPosition + LCD_HEIGHT < (uint32_t)screen_items ? ui.encoderPosition + LCD_HEIGHT : screen_items; ui.refresh(); break; case SLIDER: hold(control); ui.encoderPosition = (x - control->x) * control->data / control->width; break; - case INCREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? ubl.encoder_diff++ : ui.encoderPosition++, ui.encoderPosition++); break; - case DECREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? ubl.encoder_diff-- : ui.encoderPosition--, ui.encoderPosition--); break; + case INCREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff++ : ui.encoderPosition++, ui.encoderPosition++); break; + case DECREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff-- : ui.encoderPosition--, ui.encoderPosition--); break; case HEATER: int8_t heater; heater = control->data; @@ -189,26 +189,26 @@ void Touch::touch(touch_control_t *control) { #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); }); + MenuItem_int3::action(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); }); + MenuItem_int3::action(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_MAX_TARGET, thermalManager.start_watching_bed); + MenuItem_int3::action(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_MAX_TARGET, thermalManager.start_watching_chamber); + MenuItem_int3::action(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); + MenuItem_int3::action(GET_TEXT_F(MSG_COOLER), &thermalManager.temp_cooler.target, 0, COOLER_MAX_TARGET, thermalManager.start_watching_cooler); } #endif @@ -218,19 +218,19 @@ void Touch::touch(touch_control_t *control) { static uint8_t fan, fan_speed; fan = 0; fan_speed = thermalManager.fan_speed[fan]; - MenuItem_percent::action((const char *)GET_TEXT_F(MSG_FIRST_FAN_SPEED), &fan_speed, 0, 255, []{ thermalManager.set_fan_speed(fan, fan_speed); }); + MenuItem_percent::action(GET_TEXT_F(MSG_FIRST_FAN_SPEED), &fan_speed, 0, 255, []{ thermalManager.set_fan_speed(fan, fan_speed); }); break; case FEEDRATE: ui.clear_lcd(); - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_SPEED), &feedrate_percentage, 10, 999); + MenuItem_int3::action(GET_TEXT_F(MSG_SPEED), &feedrate_percentage, 10, 999); break; case FLOWRATE: ui.clear_lcd(); MenuItemBase::itemIndex = control->data; #if EXTRUDERS == 1 - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_FLOW), &planner.flow_percentage[MenuItemBase::itemIndex], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); + MenuItem_int3::action(GET_TEXT_F(MSG_FLOW), &planner.flow_percentage[MenuItemBase::itemIndex], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); #else - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_FLOW_N), &planner.flow_percentage[MenuItemBase::itemIndex], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); + MenuItem_int3::action(GET_TEXT_F(MSG_FLOW_N), &planner.flow_percentage[MenuItemBase::itemIndex], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); #endif break; diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 7c3d04345f48..ad9f8111815a 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -105,12 +105,12 @@ void MarlinUI::draw_kill_screen() { line++; menu_line(line++, COLOR_KILL_SCREEN_BG); - tft_string.set(GET_TEXT(MSG_HALTED)); + tft_string.set(GET_TEXT_F(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.set(GET_TEXT_F(MSG_PLEASE_RESET)); tft_string.trim(); tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); @@ -181,13 +181,13 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { tft.add_image(8, 28, image, Color); - tft_string.set((uint8_t *)i16tostr3rj(currentTemperature)); + tft_string.set(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.set(i16tostr3rj(targetTemperature)); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); tft.add_text(tft_string.center(80) + 2, 8, Color, tft_string); @@ -211,7 +211,7 @@ void draw_fan_status(uint16_t x, uint16_t y, const bool blink) { tft.add_image(8, 20, image, COLOR_FAN); - tft_string.set((uint8_t *)ui8tostr4pctrj(thermalManager.fan_speed[0])); + tft_string.set(ui8tostr4pctrj(thermalManager.fan_speed[0])); tft_string.trim(); tft.add_text(tft_string.center(80) + 6, 82, COLOR_FAN, tft_string); } @@ -271,19 +271,25 @@ void MarlinUI::draw_status_screen() { else { tft.add_text(200, 3, COLOR_AXIS_HOMED , "X"); const bool nhx = axis_should_home(X_AXIS); - tft_string.set(blink && nhx ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + if (blink && nhx) + tft_string.set('?'); + else + tft_string.set(ftostr4sign(LOGICAL_X_POSITION(current_position.x))); tft.add_text(300 - tft_string.width(), 3, nhx ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); tft.add_text(500, 3, COLOR_AXIS_HOMED , "Y"); const bool nhy = axis_should_home(Y_AXIS); - tft_string.set(blink && nhy ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + if (blink && nhy) + tft_string.set('?'); + else + tft_string.set(ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); tft.add_text(600 - tft_string.width(), 3, nhy ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); } tft.add_text(800, 3, COLOR_AXIS_HOMED , "Z"); uint16_t offset = 32; const bool nhz = axis_should_home(Z_AXIS); if (blink && nhz) - tft_string.set("?"); + tft_string.set('?'); else { const float z = LOGICAL_Z_POSITION(current_position.z); tft_string.set(ftostr52sp((int16_t)z)); @@ -352,14 +358,14 @@ void MarlinUI::draw_status_screen() { } // 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(FSTR_P const fstr, 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.set(fstr, itemIndex, itemStringC, itemStringF); tft_string.trim(); tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -388,8 +394,7 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const val } #endif - extern screenFunc_t _manual_move_func_ptr; - if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { + if (ui.can_show_slider()) { #define SLIDER_LENGTH 600 #define SLIDER_Y_POSITION 200 @@ -421,7 +426,7 @@ void TFT::draw_edit_screen_buttons() { } // 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*/) { +void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, const bool yesno, FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/) { uint16_t line = 1; if (!string) line++; @@ -473,13 +478,13 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const #endif menu_line(row); - tft_string.set(GET_TEXT(MSG_FILAMENT_CHANGE_NOZZLE)); + tft_string.set(GET_TEXT_F(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(F(" / ")); tft_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder))); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); @@ -501,14 +506,14 @@ 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++) - 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); + 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({ bedlevel.get_mesh_x(x), bedlevel.get_mesh_y(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); + 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) }, + const xy_pos_t pos = { bedlevel.get_mesh_x(x_plot), bedlevel.get_mesh_y(y_plot) }, lpos = pos.asLogical(); tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 - MENU_ITEM_HEIGHT, 120, MENU_ITEM_HEIGHT); @@ -531,7 +536,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const 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.set(isnan(bedlevel.z_values[x_plot][y_plot]) ? "-----" : ftostr43sign(bedlevel.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); @@ -596,7 +601,7 @@ MotionAxisState motionAxisState; static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, USE_BEEPER) + #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -606,20 +611,20 @@ static void quick_feedback() { #define CUR_STEP_VALUE_WIDTH 104 static void drawCurStepValue() { - tft_string.set((uint8_t *)ftostr52sp(motionAxisState.currentStepSize)); - tft_string.add("mm"); + tft_string.set(ftostr52sp(motionAxisState.currentStepSize)); + tft_string.add(F("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_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_string.set(F("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) { @@ -630,17 +635,19 @@ static void drawCurZSelection() { 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_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) { +static void drawMessage(PGM_P const 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 drawMessage(FSTR_P const fmsg) { drawMessage(FTOP(fmsg)); } + 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 :) @@ -666,7 +673,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #if ENABLED(PREVENT_COLD_EXTRUSION) if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); + drawMessage(F("Too cold")); return; } #endif @@ -693,18 +700,18 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { drawAxisValue(axis); } else { - drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + drawMessage(GET_TEXT_F(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)); + drawMessage(GET_TEXT_F(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)); + drawMessage(GET_TEXT_F(MSG_LCD_SOFT_ENDSTOPS)); } else { drawMessage(""); // clear the error @@ -733,7 +740,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #if IS_KINEMATIC UNUSED(limited); #else - PGM_P const msg = limited ? GET_TEXT(MSG_LCD_SOFT_ENDSTOPS) : NUL_STR; + FSTR_P const msg = limited ? GET_TEXT_F(MSG_LCD_SOFT_ENDSTOPS) : FPSTR(NUL_STR); drawMessage(msg); #endif @@ -766,7 +773,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } static void do_home() { quick_feedback(); - drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); + drawMessage(GET_TEXT_F(MSG_LEVEL_BED_HOMING)); queue.inject_P(G28_STR); // Disable touch until home is done TERN_(TOUCH_SCREEN, touch.disable()); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 812a03594795..56887478f0a6 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -181,13 +181,13 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { tft.add_image(0, 18, image, Color); - tft_string.set((uint8_t *)i16tostr3rj(currentTemperature)); + tft_string.set(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)); + tft_string.set(i16tostr3rj(targetTemperature)); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); tft.add_text(tft_string.center(64) + 2, 8, Color, tft_string); @@ -211,7 +211,7 @@ void draw_fan_status(uint16_t x, uint16_t y, const bool blink) { tft.add_image(0, 10, image, COLOR_FAN); - tft_string.set((uint8_t *)ui8tostr4pctrj(thermalManager.fan_speed[0])); + tft_string.set(ui8tostr4pctrj(thermalManager.fan_speed[0])); tft_string.trim(); tft.add_text(tft_string.center(64) + 6, 72, COLOR_FAN, tft_string); } @@ -282,7 +282,7 @@ void MarlinUI::draw_status_screen() { const bool nhz = axis_should_home(Z_AXIS); uint16_t offset = 25; if (blink && nhz) - tft_string.set("?"); + tft_string.set('?'); else { const float z = LOGICAL_Z_POSITION(current_position.z); tft_string.set(ftostr52sp((int16_t)z)); @@ -347,14 +347,14 @@ void MarlinUI::draw_status_screen() { } // 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(FSTR_P const fstr, 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.set(fstr, itemIndex, itemStringC, itemStringF); tft_string.trim(); tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -383,8 +383,7 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const val } #endif - extern screenFunc_t _manual_move_func_ptr; - if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { + if (ui.can_show_slider()) { #define SLIDER_LENGTH 224 #define SLIDER_Y_POSITION 140 @@ -416,7 +415,7 @@ void TFT::draw_edit_screen_buttons() { } // 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*/) { +void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, const bool yesno, FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/) { uint16_t line = 1; if (!string) line++; @@ -461,7 +460,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.add(' '); tft_string.add(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); tft_string.add(LCD_STR_DEGREE); - tft_string.add(" / "); + tft_string.add(F(" / ")); tft_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder))); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); @@ -485,12 +484,12 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const 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) })) + if (position_is_reachable({ bedlevel.get_mesh_x(x), bedlevel.get_mesh_y(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) }, + const xy_pos_t pos = { bedlevel.get_mesh_x(x_plot), bedlevel.get_mesh_y(y_plot) }, lpos = pos.asLogical(); tft.canvas(216, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 - MENU_ITEM_HEIGHT, 96, MENU_ITEM_HEIGHT); @@ -513,7 +512,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const 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.set(isnan(bedlevel.z_values[x_plot][y_plot]) ? "-----" : ftostr43sign(bedlevel.z_values[x_plot][y_plot])); tft_string.trim(); tft.add_text(96 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string); @@ -578,7 +577,7 @@ MotionAxisState motionAxisState; static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, USE_BEEPER) + #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -588,24 +587,24 @@ static void quick_feedback() { #define CUR_STEP_VALUE_WIDTH 38 static void drawCurStepValue() { - tft_string.set((uint8_t *)ftostr52sp(motionAxisState.currentStepSize)); + tft_string.set(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_string.set(F("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_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_string.set(F("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) { @@ -616,17 +615,19 @@ static void drawCurZSelection() { 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_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) { +static void drawMessage(PGM_P const 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 drawMessage(FSTR_P const fmsg) { drawMessage(FTOP(fmsg)); } + 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 :) @@ -652,7 +653,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #if ENABLED(PREVENT_COLD_EXTRUSION) if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); + drawMessage(F("Too cold")); return; } #endif @@ -675,25 +676,25 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { probe.offset.z = new_offs; else TERN(BABYSTEP_HOTEND_Z_OFFSET, hotend_offset[active_extruder].z = new_offs, NOOP); - drawMessage(""); // clear the error + drawMessage(NUL_STR); // clear the error drawAxisValue(axis); } else { - drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + drawMessage(GET_TEXT_F(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)); + drawMessage(GET_TEXT_F(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)); + drawMessage(GET_TEXT_F(MSG_LCD_SOFT_ENDSTOPS)); } else { - drawMessage(""); // clear the error + drawMessage(NUL_STR); // clear the error } drawAxisValue(axis); #endif @@ -752,7 +753,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } static void do_home() { quick_feedback(); - drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); + drawMessage(GET_TEXT_F(MSG_LEVEL_BED_HOMING)); queue.inject_P(G28_STR); // Disable touch until home is done TERN_(HAS_TFT_XPT2046, touch.disable()); diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index f142dbbc06c1..d4a04d690080 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -181,13 +181,13 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { tft.add_image(8, 28, image, Color); - tft_string.set((uint8_t *)i16tostr3rj(currentTemperature)); + tft_string.set(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.set(i16tostr3rj(targetTemperature)); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); tft.add_text(tft_string.center(80) + 2, 8, Color, tft_string); @@ -211,7 +211,7 @@ void draw_fan_status(uint16_t x, uint16_t y, const bool blink) { tft.add_image(8, 20, image, COLOR_FAN); - tft_string.set((uint8_t *)ui8tostr4pctrj(thermalManager.fan_speed[0])); + tft_string.set(ui8tostr4pctrj(thermalManager.fan_speed[0])); tft_string.trim(); tft.add_text(tft_string.center(80) + 6, 82, COLOR_FAN, tft_string); } @@ -283,7 +283,7 @@ void MarlinUI::draw_status_screen() { uint16_t offset = 32; const bool nhz = axis_should_home(Z_AXIS); if (blink && nhz) - tft_string.set("?"); + tft_string.set('?'); else { const float z = LOGICAL_Z_POSITION(current_position.z); tft_string.set(ftostr52sp((int16_t)z)); @@ -352,14 +352,14 @@ void MarlinUI::draw_status_screen() { } // 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(FSTR_P const fstr, 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.set(fstr, itemIndex, itemStringC, itemStringF); tft_string.trim(); tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); @@ -388,8 +388,7 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const val } #endif - extern screenFunc_t _manual_move_func_ptr; - if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { + if (ui.can_show_slider()) { #define SLIDER_LENGTH 336 #define SLIDER_Y_POSITION 186 @@ -421,7 +420,7 @@ void TFT::draw_edit_screen_buttons() { } // 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*/) { +void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, const bool yesno, FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/) { uint16_t line = 1; if (!string) line++; @@ -466,7 +465,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const tft_string.add(' '); tft_string.add(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); tft_string.add(LCD_STR_DEGREE); - tft_string.add(" / "); + tft_string.add(F(" / ")); tft_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder))); tft_string.add(LCD_STR_DEGREE); tft_string.trim(); @@ -490,12 +489,12 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const 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) })) + if (position_is_reachable({ bedlevel.get_mesh_x(x), bedlevel.get_mesh_y(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) }, + const xy_pos_t pos = { bedlevel.get_mesh_x(x_plot), bedlevel.get_mesh_y(y_plot) }, lpos = pos.asLogical(); tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 - MENU_ITEM_HEIGHT, 120, MENU_ITEM_HEIGHT); @@ -518,7 +517,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const 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.set(isnan(bedlevel.z_values[x_plot][y_plot]) ? "-----" : ftostr43sign(bedlevel.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); @@ -583,7 +582,7 @@ MotionAxisState motionAxisState; static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, USE_BEEPER) + #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -593,20 +592,20 @@ static void quick_feedback() { #define CUR_STEP_VALUE_WIDTH 104 static void drawCurStepValue() { - tft_string.set((uint8_t *)ftostr52sp(motionAxisState.currentStepSize)); - tft_string.add("mm"); + tft_string.set(ftostr52sp(motionAxisState.currentStepSize)); + tft_string.add(F("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_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_string.set(F("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) { @@ -617,17 +616,19 @@ static void drawCurZSelection() { 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_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) { +static void drawMessage(PGM_P const 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 drawMessage(FSTR_P const fmsg) { drawMessage(FTOP(fmsg)); } + 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 :) @@ -653,7 +654,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #if ENABLED(PREVENT_COLD_EXTRUSION) if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); + drawMessage(F("Too cold")); return; } #endif @@ -676,25 +677,25 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { probe.offset.z = new_offs; else TERN(BABYSTEP_HOTEND_Z_OFFSET, hotend_offset[active_extruder].z = new_offs, NOOP); - drawMessage(""); // clear the error + drawMessage(NUL_STR); // clear the error drawAxisValue(axis); } else { - drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + drawMessage(GET_TEXT_F(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)); + drawMessage(GET_TEXT_F(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)); + drawMessage(GET_TEXT_F(MSG_LCD_SOFT_ENDSTOPS)); } else { - drawMessage(""); // clear the error + drawMessage(NUL_STR); // clear the error } drawAxisValue(axis); #endif @@ -753,7 +754,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } static void do_home() { quick_feedback(); - drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); + drawMessage(GET_TEXT_F(MSG_LEVEL_BED_HOMING)); queue.inject_P(G28_STR); // Disable touch until home is done TERN_(HAS_TFT_XPT2046, touch.disable()); diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp index acc91f51fa83..bb0578576632 100644 --- a/Marlin/src/lcd/tft/ui_common.cpp +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -96,16 +96,15 @@ 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) { +int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { if (max_length < 1) return 0; - tft_string.set(); - tft_string.add(c); + tft_string.set(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_pstr, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P utf8_pstr, const pixel_len_t max_length) { if (max_length < 1) return 0; tft_string.set(utf8_pstr); tft_string.trim(); @@ -115,7 +114,7 @@ int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { return tft_string.width(); } -int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { +int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { return lcd_put_u8str_max_P(utf8_str, max_length); } @@ -130,10 +129,10 @@ void lcd_put_int(const int i) { // // 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) { +void MenuItemBase::_draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char pre_char, const char post_char) { menu_item(row, sel); - uint8_t *string = (uint8_t *)pstr; + const char *string = FTOP(fstr); MarlinImage image = noImage; switch (*string) { case 0x01: image = imgRefresh; break; // LCD_STR_REFRESH @@ -147,33 +146,34 @@ void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, co 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_string.set(string, itemIndex, itemStringC, itemStringF); + 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) { +void MenuEditItemBase::draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char * const inStr, const bool pgm) { menu_item(row, sel); - tft_string.set(pstr, itemIndex, itemString); + tft_string.set(fstr, itemIndex, itemStringC, itemStringF); tft.add_text(MENU_TEXT_X_OFFSET, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); - if (data) { - tft_string.set(data); + if (inStr) { + tft_string.set(inStr); 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*/) { +void MenuItem_static::draw(const uint8_t row, FSTR_P const fstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { menu_item(row); - tft_string.set(pstr, itemIndex, itemString); + tft_string.set(fstr, itemIndex, itemStringC, itemStringF); 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) { + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_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); constexpr uint8_t maxlen = (MENU_ITEM_HEIGHT) - (MENU_TEXT_Y_OFFSET) + 1; diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index dcdc7def8667..604f366ed4f2 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -68,26 +68,31 @@ uint8_t TouchButtons::read_buttons() { #ifdef HAS_WIRED_LCD int16_t x, 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 HAS_TOUCH_SLEEP - if (is_touched) - wakeUp(); - else if (!isSleeping() && ELAPSED(millis(), next_sleep_ms) && ui.on_status_screen()) - sleepTimeout(); - #endif - if (!is_touched) return 0; - - #if ENABLED(TOUCH_SCREEN_CALIBRATION) - const calibrationState state = touch_calibration.get_calibration_state(); - if (WITHIN(state, CALIBRATION_TOP_LEFT, 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; + #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) + 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 HAS_TOUCH_SLEEP + if (is_touched) + wakeUp(); + else if (!isSleeping() && ELAPSED(millis(), next_sleep_ms) && ui.on_status_screen()) + sleepTimeout(); + #endif + if (!is_touched) return 0; + + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + const calibrationState state = touch_calibration.get_calibration_state(); + if (WITHIN(state, CALIBRATION_TOP_LEFT, 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 + #elif ENABLED(TFT_TOUCH_DEVICE_GT911) + bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? touchIO.getPoint(&y, &x) : touchIO.getPoint(&x, &y)); + if (!is_touched) return 0; #endif // Touch within the button area simulates an encoder button diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index 6407fac67086..4b5a23e4c550 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -48,17 +48,17 @@ #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 +#elif defined(STM32F1) || defined(STM32F4) #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) -#define IIC_SCL_1() WRITE(IIC_EEPROM_SCL, HIGH) -#define IIC_SDA_0() WRITE(IIC_EEPROM_SDA, LOW) -#define IIC_SDA_1() WRITE(IIC_EEPROM_SDA, HIGH) -#define READ_SDA() READ(IIC_EEPROM_SDA) +#define IIC_SCL_0() WRITE(IIC_EEPROM_SCL, LOW) +#define IIC_SCL_1() WRITE(IIC_EEPROM_SCL, HIGH) +#define IIC_SDA_0() WRITE(IIC_EEPROM_SDA, LOW) +#define IIC_SDA_1() WRITE(IIC_EEPROM_SDA, HIGH) +#define READ_SDA() READ(IIC_EEPROM_SDA) // // Simple IIC interface via libmaple diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index 30c837432440..1d6943406722 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -38,7 +38,7 @@ L64XX_Marlin L64xxManager; #include "../../HAL/shared/Delay.h" static const char NUM_AXIS_LIST( - str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", + str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", str_I[] PROGMEM = STR_I " ", str_J[] PROGMEM = STR_J " ", str_K[] PROGMEM = STR_K " " ), str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2", @@ -66,14 +66,14 @@ void echo_yes_no(const bool yes) { DEBUG_ECHOPGM_P(yes ? PSTR(" YES") : PSTR(" N uint8_t L64XX_Marlin::dir_commands[MAX_L64XX]; // array to hold direction command for each driver -#define _EN_ITEM(N) , INVERT_E##N##_DIR +#define _EN_ITEM(N) , ENABLED(INVERT_E##N##_DIR) const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = { - NUM_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 + NUM_AXIS_LIST(ENABLED(INVERT_X_DIR), ENABLED(INVERT_Y_DIR), ENABLED(INVERT_Z_DIR), ENABLED(INVERT_I_DIR), ENABLED(INVERT_J_DIR), ENABLED(INVERT_K_DIR), ENABLED(INVERT_U_DIR), ENABLED(INVERT_V_DIR), ENABLED(INVERT_W_DIR)) + , ENABLED(INVERT_X_DIR) ^ BOTH(HAS_DUAL_X_STEPPERS, INVERT_X2_VS_X_DIR) // X2 + , ENABLED(INVERT_Y_DIR) ^ BOTH(HAS_DUAL_Y_STEPPERS, INVERT_Y2_VS_Y_DIR) // Y2 + , ENABLED(INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2 + , ENABLED(INVERT_Z_DIR) ^ ENABLED(INVERT_Z3_VS_Z_DIR) // Z3 + , ENABLED(INVERT_Z_DIR) ^ ENABLED(INVERT_Z4_VS_Z_DIR) // Z4 REPEAT(E_STEPPERS, _EN_ITEM) }; #undef _EN_ITEM diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.h b/Marlin/src/libs/L64XX/L64XX_Marlin.h index b71d97a0d6fb..e8d8498ac7a6 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.h +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.h @@ -36,7 +36,7 @@ #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)) #define _EN_ITEM(N) , E##N -enum L64XX_axis_t : uint8_t { NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX }; +enum L64XX_axis_t : uint8_t { MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX }; #undef _EN_ITEM class L64XX_Marlin : public L64XXHelper { diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index c042504cf872..0d709b1b0b42 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -133,13 +133,13 @@ SPISettings MAX31865::spiConfig = SPISettings( /** * 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. - * @param wire The resistance of the wire connecting the sensor to the RTD, in ohms. + * @param wires The number of wires as an enum: MAX31865_2WIRE, MAX31865_3WIRE, or MAX31865_4WIRE. + * @param zero_res The resistance of the RTD at 0°C, in ohms. + * @param ref_res The resistance of the reference resistor, in ohms. + * @param wire_res The resistance of the wire connecting the sensor to the RTD, in ohms. */ -void MAX31865::begin(max31865_numwires_t wires, float zero_res, float ref_res, float wire_res) { - zeroRes = zero_res; +void MAX31865::begin(max31865_numwires_t wires, const_float_t zero_res, const_float_t ref_res, const_float_t wire_res) { + resNormalizer = 100.0f / zero_res; // reciprocal of resistance, scaled by 100 refRes = ref_res; wireRes = wire_res; @@ -437,42 +437,61 @@ float MAX31865::temperature() { * * @return Temperature in C */ -float MAX31865::temperature(uint16_t adc_val) { +float MAX31865::temperature(const uint16_t adc_val) { return temperature(((adc_val) * RECIPROCAL(32768.0f)) * refRes - wireRes); } /** * 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 rtd_res the resistance value in ohms - * @return the temperature in degC + * @return the temperature in °C */ float MAX31865::temperature(float rtd_res) { + + rtd_res *= resNormalizer; // normalize to 100 ohm + + // Constants for calculating temperature from the measured RTD resistance. + // http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf + constexpr float RTD_Z1 = -0.0039083, + RTD_Z2 = +1.758480889e-5, + RTD_Z3 = -2.31e-8, + RTD_Z4 = -1.155e-6; + + // Callender-Van Dusen equation float temp = (RTD_Z1 + sqrt(RTD_Z2 + (RTD_Z3 * rtd_res))) * RECIPROCAL(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. + // of resistance. So here we use a Linear Approximation instead. // if (temp < 0) { - rtd_res = (rtd_res / zeroRes) * 100; // normalize to 100 ohm - float rpoly = rtd_res; + #ifndef MAX31865_APPROX + #define MAX31865_APPROX 5 + #endif + + constexpr float RTD_C[] = { + #if MAX31865_APPROX == 5 + -242.02, +2.2228, +2.5859e-3, -4.8260e-6, -2.8183e-8, +1.5243e-10 + #elif MAX31865_APPROX == 4 + -241.96, +2.2163, +2.8541e-3, -9.9121e-6, -1.7152e-8 + #elif MAX31865_APPROX == 3 + -242.09, +2.2276, +2.5178e-3, -5.8620e-6 + #else + -242.97, +2.2838, +1.4727e-3 + #endif + }; - temp = -242.02 + (2.2228 * rpoly); - rpoly *= rtd_res; // square - temp += 2.5859e-3 * rpoly; - rpoly *= rtd_res; // ^3 - temp -= 4.8260e-6 * rpoly; - rpoly *= rtd_res; // ^4 - temp -= 2.8183e-8 * rpoly; - rpoly *= rtd_res; // ^5 - temp += 1.5243e-10 * rpoly; + float rpoly = rtd_res; + temp = RTD_C[0]; + temp += rpoly * RTD_C[1]; + rpoly *= rtd_res; temp += rpoly * RTD_C[2]; + if (MAX31865_APPROX >= 3) rpoly *= rtd_res; temp += rpoly * RTD_C[3]; + if (MAX31865_APPROX >= 4) rpoly *= rtd_res; temp += rpoly * RTD_C[4]; + if (MAX31865_APPROX >= 5) rpoly *= rtd_res; temp += rpoly * RTD_C[5]; } return temp; diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index baea455485d4..95bde756cee7 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -73,13 +73,6 @@ #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, @@ -103,7 +96,7 @@ class MAX31865 { uint16_t spiDelay; - float zeroRes, refRes, wireRes; + float resNormalizer, refRes, wireRes; #if ENABLED(MAX31865_USE_READ_ERROR_DETECTION) millis_t lastReadStamp = 0; @@ -160,7 +153,7 @@ class MAX31865 { int8_t spi_clk); #endif - void begin(max31865_numwires_t wires, float zero_res, float ref_res, float wire_res); + void begin(max31865_numwires_t wires, const_float_t zero_res, const_float_t ref_res, const_float_t wire_res); uint8_t readFault(); void clearFault(); @@ -168,6 +161,6 @@ class MAX31865 { uint16_t readRaw(); float readResistance(); float temperature(); - float temperature(uint16_t adc_val); + float temperature(const uint16_t adc_val); float temperature(float rtd_res); }; diff --git a/Marlin/src/libs/bresenham.h b/Marlin/src/libs/bresenham.h index 865c43c29e0b..39ab60700769 100644 --- a/Marlin/src/libs/bresenham.h +++ b/Marlin/src/libs/bresenham.h @@ -30,7 +30,7 @@ */ #define FORCE_INLINE __attribute__((always_inline)) inline -#define _O3 __attribute__((optimize("O3"))) +#define __O3 __attribute__((optimize("O3"))) template struct BresenhamCfg { static constexpr uint8_t UID = uid, SIZE = size; }; @@ -114,9 +114,9 @@ class Bresenham { if (tick1(index)) { value[index] += dir[index]; back(index); } } - FORCE_INLINE static void tick1() _O3 { for (uint8_t i = 0; i < Cfg::SIZE; i++) (void)tick1(i); } + FORCE_INLINE static void tick1() __O3 { for (uint8_t i = 0; i < Cfg::SIZE; i++) (void)tick1(i); } - FORCE_INLINE static void tick() _O3 { for (uint8_t i = 0; i < Cfg::SIZE; i++) (void)tick(i); } + FORCE_INLINE static void tick() __O3 { for (uint8_t i = 0; i < Cfg::SIZE; i++) (void)tick(i); } static void report(const uint8_t index) { if (index < Cfg::SIZE) { diff --git a/Marlin/src/libs/buzzer.cpp b/Marlin/src/libs/buzzer.cpp index 57ed5fb41910..1e2f23c5fdef 100644 --- a/Marlin/src/libs/buzzer.cpp +++ b/Marlin/src/libs/buzzer.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if USE_BEEPER +#if HAS_BEEPER #include "buzzer.h" #include "../module/temperature.h" @@ -45,17 +45,17 @@ 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; + if (!ui.sound_on) return; while (buffer.isFull()) { tick(); - thermalManager.manage_heater(); + thermalManager.task(); } tone_t tone = { duration, frequency }; buffer.enqueue(tone); } void Buzzer::tick() { - if (!ui.buzzer_enabled) return; + if (!ui.sound_on) return; const millis_t now = millis(); if (!state.endtime) { @@ -81,4 +81,4 @@ void Buzzer::tick() { else if (ELAPSED(now, state.endtime)) reset(); } -#endif // USE_BEEPER +#endif // HAS_BEEPER diff --git a/Marlin/src/libs/buzzer.h b/Marlin/src/libs/buzzer.h index 73406c0591be..b1c286a66222 100644 --- a/Marlin/src/libs/buzzer.h +++ b/Marlin/src/libs/buzzer.h @@ -23,7 +23,7 @@ #include "../inc/MarlinConfig.h" -#if USE_BEEPER +#if HAS_BEEPER #include "circularqueue.h" @@ -61,18 +61,6 @@ */ FORCE_INLINE static void invert() { TOGGLE(BEEPER_PIN); } - /** - * @brief Turn off a digital PIN - * @details Alias of digitalWrite(PIN, LOW) using FastIO - */ - FORCE_INLINE static void off() { WRITE(BEEPER_PIN, LOW); } - - /** - * @brief Turn on a digital PIN - * @details Alias of digitalWrite(PIN, HIGH) using FastIO - */ - FORCE_INLINE static void on() { WRITE(BEEPER_PIN, HIGH); } - /** * @brief Resets the state of the class * @details Brings the class state to a known one. @@ -91,6 +79,20 @@ reset(); } + /** + * @brief Turn on a digital PIN + * @details Alias of digitalWrite(PIN, HIGH) using FastIO + */ + FORCE_INLINE static void on() { WRITE(BEEPER_PIN, HIGH); } + + /** + * @brief Turn off a digital PIN + * @details Alias of digitalWrite(PIN, LOW) using FastIO + */ + FORCE_INLINE static void off() { WRITE(BEEPER_PIN, LOW); } + + static void click(const uint16_t duration) { on(); delay(duration); off(); } + /** * @brief Add a tone to the queue * @details Adds a tone_t structure to the ring buffer, will block IO if the @@ -118,8 +120,8 @@ #elif HAS_BUZZER // Buzz indirectly via the MarlinUI instance - #include "../lcd/marlinui.h" #define BUZZ(d,f) ui.buzz(d,f) + #include "../lcd/marlinui.h" #else diff --git a/Marlin/src/libs/nozzle.h b/Marlin/src/libs/nozzle.h index 7bbd0e35c11b..69790f5a6786 100644 --- a/Marlin/src/libs/nozzle.h +++ b/Marlin/src/libs/nozzle.h @@ -41,7 +41,7 @@ class Nozzle { * @param end xyz_pos_t defining the ending point * @param strokes number of strokes to execute */ - static void stroke(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes) _Os; + static void stroke(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes) __Os; /** * @brief Zig-zag clean pattern @@ -52,7 +52,7 @@ class Nozzle { * @param strokes number of strokes to execute * @param objects number of objects to create */ - static void zigzag(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes, const uint8_t &objects) _Os; + static void zigzag(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes, const uint8_t &objects) __Os; /** * @brief Circular clean pattern @@ -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_t 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,14 +77,14 @@ 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_t 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; + 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/module/delta.cpp b/Marlin/src/module/delta.cpp index 39eb15f896da..ce2a6f4adad0 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -236,6 +236,9 @@ void home_delta() { TERN_(U_SENSORLESS, sensorless_t stealth_states_u = start_sensorless_homing_per_axis(U_AXIS)); TERN_(V_SENSORLESS, sensorless_t stealth_states_v = start_sensorless_homing_per_axis(V_AXIS)); TERN_(W_SENSORLESS, sensorless_t stealth_states_w = start_sensorless_homing_per_axis(W_AXIS)); + #if SENSORLESS_STALLGUARD_DELAY + safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle + #endif #endif // Move all carriages together linearly until an endstop is hit. @@ -255,6 +258,9 @@ void home_delta() { TERN_(U_SENSORLESS, end_sensorless_homing_per_axis(U_AXIS, stealth_states_u)); TERN_(V_SENSORLESS, end_sensorless_homing_per_axis(V_AXIS, stealth_states_v)); TERN_(W_SENSORLESS, end_sensorless_homing_per_axis(W_AXIS, stealth_states_w)); + #if SENSORLESS_STALLGUARD_DELAY + safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle + #endif #endif endstops.validate_homing_move(); diff --git a/Marlin/src/module/delta.h b/Marlin/src/module/delta.h index 7cd42805c90a..0a0c6124eecf 100644 --- a/Marlin/src/module/delta.h +++ b/Marlin/src/module/delta.h @@ -45,6 +45,13 @@ extern abc_float_t delta_diagonal_rod_trim; */ void recalc_delta_settings(); +/** + * Get a safe radius for calibration + */ +#if HAS_DELTA_SENSORLESS_PROBING + static constexpr float sensorless_radius_factor = 0.7f; +#endif + /** * Delta Inverse Kinematics * diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 7381e98b01b2..1ee4b92b5f36 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -31,6 +31,9 @@ #include "temperature.h" #include "../lcd/marlinui.h" +#define DEBUG_OUT BOTH(USE_SENSORLESS, DEBUG_LEVELING_FEATURE) +#include "../core/debug_out.h" + #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) #include HAL_PATH(../HAL, endstop_interrupts.h) #endif @@ -78,9 +81,9 @@ Endstops::endstop_mask_t Endstops::live_state = 0; #endif #if ENABLED(Z_MULTI_ENDSTOPS) float Endstops::z2_endstop_adj; - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 float Endstops::z3_endstop_adj; - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 float Endstops::z4_endstop_adj; #endif #endif @@ -560,7 +563,7 @@ static void print_es_state(const bool is_hit, FSTR_P const flabel=nullptr) { #pragma GCC diagnostic pop -void _O2 Endstops::report_states() { +void __O2 Endstops::report_states() { TERN_(BLTOUCH, bltouch._set_SW_mode()); SERIAL_ECHOLNPGM(STR_M119_REPORT); #define ES_REPORT(S) print_es_state(READ(S##_PIN) != S##_ENDSTOP_INVERTING, F(STR_##S)) @@ -703,7 +706,7 @@ void Endstops::update() { #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) #define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT)) - #if ENABLED(G38_PROBE_TARGET) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_XY) + #if ENABLED(G38_PROBE_TARGET) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_YX) #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)); @@ -714,7 +717,7 @@ void Endstops::update() { #define X_MAX_TEST() TERN1(DUAL_X_CARRIAGE, TERN0(X_HOME_TO_MAX, stepper.last_moved_extruder == 0) || TERN0(X2_HOME_TO_MAX, stepper.last_moved_extruder != 0)) // Use HEAD for core axes, AXIS for others - #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_XY) + #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_YX) #define X_AXIS_HEAD X_HEAD #else #define X_AXIS_HEAD X_AXIS @@ -792,14 +795,14 @@ void Endstops::update() { #else COPY_LIVE_STATE(Z_MIN, Z2_MIN); #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 #if HAS_Z3_MIN UPDATE_ENDSTOP_BIT(Z3, MIN); #else COPY_LIVE_STATE(Z_MIN, Z3_MIN); #endif #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 #if HAS_Z4_MIN UPDATE_ENDSTOP_BIT(Z4, MIN); #else @@ -824,14 +827,14 @@ void Endstops::update() { #else COPY_LIVE_STATE(Z_MAX, Z2_MAX); #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 #if HAS_Z3_MAX UPDATE_ENDSTOP_BIT(Z3, MAX); #else COPY_LIVE_STATE(Z_MAX, Z3_MAX); #endif #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 #if HAS_Z4_MAX UPDATE_ENDSTOP_BIT(Z4, MAX); #else @@ -1090,9 +1093,9 @@ void Endstops::update() { #if DISABLED(Z_MULTI_ENDSTOPS) #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_ENDSTOP(Z, MINMAX) - #elif NUM_Z_STEPPER_DRIVERS == 4 + #elif NUM_Z_STEPPERS == 4 #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_QUAD_ENDSTOP(Z, MINMAX) - #elif NUM_Z_STEPPER_DRIVERS == 3 + #elif NUM_Z_STEPPERS == 3 #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_TRIPLE_ENDSTOP(Z, MINMAX) #else #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX) @@ -1621,3 +1624,66 @@ void Endstops::update() { } #endif // PINS_DEBUGGING + +#if USE_SENSORLESS + /** + * Change TMC driver currents to N##_CURRENT_HOME, saving the current configuration of each. + */ + void Endstops::set_homing_current(const bool onoff) { + #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT) + #define HAS_DELTA_X_CURRENT (ENABLED(DELTA) && HAS_CURRENT_HOME(X)) + #define HAS_DELTA_Y_CURRENT (ENABLED(DELTA) && HAS_CURRENT_HOME(Y)) + #if HAS_DELTA_X_CURRENT || HAS_DELTA_Y_CURRENT || HAS_CURRENT_HOME(Z) + #if HAS_DELTA_X_CURRENT + static int16_t saved_current_x; + #endif + #if HAS_DELTA_Y_CURRENT + static int16_t saved_current_y; + #endif + #if HAS_CURRENT_HOME(Z) + static int16_t saved_current_z; + #endif + auto debug_current_on = [](PGM_P const s, const int16_t a, const int16_t b) { + if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b); } + }; + if (onoff) { + #if HAS_DELTA_X_CURRENT + 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_DELTA_Y_CURRENT + saved_current_y = stepperY.getMilliamps(); + stepperY.rms_current(Y_CURRENT_HOME); + debug_current_on(PSTR("Y"), saved_current_y, Y_CURRENT_HOME); + #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 + } + else { + #if HAS_DELTA_X_CURRENT + stepperX.rms_current(saved_current_x); + debug_current_on(PSTR("X"), X_CURRENT_HOME, saved_current_x); + #endif + #if HAS_DELTA_Y_CURRENT + stepperY.rms_current(saved_current_y); + debug_current_on(PSTR("Y"), Y_CURRENT_HOME, saved_current_y); + #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(onoff)); + + #if SENSORLESS_STALLGUARD_DELAY + safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle + #endif + + #endif // XYZ + } +#endif diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 1848e6cdcf2c..9e411adbdaee 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -64,11 +64,11 @@ enum EndstopEnum : char { #if ENABLED(Z_MULTI_ENDSTOPS) _ES_ITEM(HAS_Z_MIN, Z2_MIN) _ES_ITEM(HAS_Z_MAX, Z2_MAX) - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 _ES_ITEM(HAS_Z_MIN, Z3_MIN) _ES_ITEM(HAS_Z_MAX, Z3_MAX) #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 _ES_ITEM(HAS_Z_MIN, Z4_MIN) _ES_ITEM(HAS_Z_MAX, Z4_MAX) #endif @@ -120,10 +120,10 @@ class Endstops { #if ENABLED(Z_MULTI_ENDSTOPS) static float z2_endstop_adj; #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPERS >= 3 static float z3_endstop_adj; #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPERS >= 4 static float z4_endstop_adj; #endif @@ -247,6 +247,11 @@ class Endstops { static void clear_endstop_state(); static bool tmc_spi_homing_check(); #endif + public: + // Basic functions for Sensorless Homing + #if USE_SENSORLESS + static void set_homing_current(const bool onoff); + #endif }; extern Endstops endstops; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 5195ad400f25..b3b607e677a8 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -427,7 +427,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { #if UBL_SEGMENTED // UBL segmented line will do Z-only moves in single segment - ubl.line_to_destination_segmented(scaled_fr_mm_s); + bedlevel.line_to_destination_segmented(scaled_fr_mm_s); #else if (current_position == destination) return; @@ -738,10 +738,12 @@ void restore_feedrate_and_scaling() { #if HAS_SOFTWARE_ENDSTOPS // Software Endstops are based on the configured limits. + #define _AMIN(A) A##_MIN_POS + #define _AMAX(A) A##_MAX_POS soft_endstops_t soft_endstop = { true, false, - NUM_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS, U_MIN_POS, V_MIN_POS, W_MIN_POS), - NUM_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS, U_MAX_POS, V_MAX_POS, W_MAX_POS) + { MAPLIST(_AMIN, MAIN_AXIS_NAMES) }, + { MAPLIST(_AMAX, MAIN_AXIS_NAMES) }, }; /** @@ -958,15 +960,13 @@ void restore_feedrate_and_scaling() { #endif // !HAS_SOFTWARE_ENDSTOPS -#if !UBL_SEGMENTED - FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { const millis_t ms = millis(); if (ELAPSED(ms, next_idle_ms)) { next_idle_ms = ms + 200UL; return idle(); } - thermalManager.manage_heater(); // Returns immediately on most calls + thermalManager.task(); // Returns immediately on most calls } #if IS_KINEMATIC @@ -995,7 +995,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { * small incremental moves for DELTA or SCARA. * * For Unified Bed Leveling (Delta or Segmented Cartesian) - * the ubl.line_to_destination_segmented method replaces this. + * the bedlevel.line_to_destination_segmented method replaces this. * * For Auto Bed Leveling (Bilinear) with SEGMENT_LEVELED_MOVES * this is replaced by segmented_line_to_destination below. @@ -1076,7 +1076,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { #else // !IS_KINEMATIC - #if ENABLED(SEGMENT_LEVELED_MOVES) + #if ENABLED(SEGMENT_LEVELED_MOVES) && DISABLED(AUTO_BED_LEVELING_UBL) /** * Prepare a segmented move on a CARTESIAN setup. @@ -1136,7 +1136,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)); } - #endif // SEGMENT_LEVELED_MOVES + #endif // SEGMENT_LEVELED_MOVES && !AUTO_BED_LEVELING_UBL /** * Prepare a linear move in a Cartesian setup. @@ -1151,8 +1151,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { #if HAS_MESH if (planner.leveling_active && planner.leveling_active_at_z(destination.z)) { #if ENABLED(AUTO_BED_LEVELING_UBL) - ubl.line_to_destination_cartesian(scaled_fr_mm_s, active_extruder); // UBL's motion routine needs to know about - return true; // all moves, including Z-only moves. + #if UBL_SEGMENTED + return bedlevel.line_to_destination_segmented(scaled_fr_mm_s); + #else + bedlevel.line_to_destination_cartesian(scaled_fr_mm_s, active_extruder); // UBL's motion routine needs to know about + return true; // all moves, including Z-only moves. + #endif #elif ENABLED(SEGMENT_LEVELED_MOVES) segmented_line_to_destination(scaled_fr_mm_s); return false; // caller will update current_position @@ -1163,9 +1167,9 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { */ if (xy_pos_t(current_position) != xy_pos_t(destination)) { #if ENABLED(MESH_BED_LEVELING) - mbl.line_to_destination(scaled_fr_mm_s); + bedlevel.line_to_destination(scaled_fr_mm_s); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - bbl.line_to_destination(scaled_fr_mm_s); + bedlevel.line_to_destination(scaled_fr_mm_s); #endif return true; } @@ -1178,7 +1182,6 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { } #endif // !IS_KINEMATIC -#endif // !UBL_SEGMENTED #if HAS_DUPLICATION_MODE bool extruder_duplication_enabled; @@ -1363,7 +1366,7 @@ void prepare_line_to_destination() { if ( #if UBL_SEGMENTED #if IS_KINEMATIC // UBL using Kinematic / Cartesian cases as a workaround for now. - ubl.line_to_destination_segmented(MMS_SCALED(feedrate_mm_s)) + bedlevel.line_to_destination_segmented(MMS_SCALED(feedrate_mm_s)) #else line_to_destination_cartesian() #endif @@ -1379,10 +1382,10 @@ void prepare_line_to_destination() { #if HAS_ENDSTOPS - linear_axis_bits_t axis_homed, axis_trusted; // = 0 + main_axes_bits_t axes_homed, axes_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) { + main_axes_bits_t axes_should_home(main_axes_bits_t axis_bits/*=main_axes_mask*/) { + auto set_should = [](main_axes_bits_t &b, AxisEnum a) { if (TEST(b, a) && TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(a)) CBI(b, a); }; @@ -1395,23 +1398,12 @@ void prepare_line_to_destination() { return axis_bits; } - bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) { + bool homing_needed_error(main_axes_bits_t axis_bits/*=main_axes_mask*/) { if ((axis_bits = axes_should_home(axis_bits))) { PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); char msg[30]; - sprintf_P(msg, home_first, - NUM_AXIS_LIST( - TEST(axis_bits, X_AXIS) ? STR_A : "", - TEST(axis_bits, Y_AXIS) ? STR_B : "", - TEST(axis_bits, Z_AXIS) ? STR_C : "", - TEST(axis_bits, I_AXIS) ? STR_I : "", - TEST(axis_bits, J_AXIS) ? STR_J : "", - TEST(axis_bits, K_AXIS) ? STR_K : "", - TEST(axis_bits, U_AXIS) ? STR_U : "", - TEST(axis_bits, V_AXIS) ? STR_V : "", - TEST(axis_bits, W_AXIS) ? STR_W : "" - ) - ); + #define _AXIS_CHAR(N) TEST(axis_bits, _AXIS(N)) ? STR_##N : "" + sprintf_P(msg, home_first, MAPLIST(_AXIS_CHAR, MAIN_AXIS_NAMES)); SERIAL_ECHO_START(); SERIAL_ECHOLN(msg); ui.set_status(msg); @@ -1671,7 +1663,12 @@ void prepare_line_to_destination() { } // Disable stealthChop if used. Enable diag1 pin on driver. - TERN_(SENSORLESS_HOMING, stealth_states = start_sensorless_homing_per_axis(axis)); + #if ENABLED(SENSORLESS_HOMING) + stealth_states = start_sensorless_homing_per_axis(axis); + #if SENSORLESS_STALLGUARD_DELAY + safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle + #endif + #endif } #if EITHER(MORGAN_SCARA, MP_SCARA) @@ -1707,7 +1704,12 @@ void prepare_line_to_destination() { 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)); + #if ENABLED(SENSORLESS_HOMING) + end_sensorless_homing_per_axis(axis, stealth_states); + #if SENSORLESS_STALLGUARD_DELAY + safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle + #endif + #endif } } @@ -1754,7 +1756,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(X); phaseCurrent = stepperX.get_microstep_counter(); effectorBackoutDir = -X_HOME_DIR; - stepperBackoutDir = INVERT_X_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_X_DIR, -)effectorBackoutDir; break; #endif #ifdef Y_MICROSTEPS @@ -1762,7 +1764,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(Y); phaseCurrent = stepperY.get_microstep_counter(); effectorBackoutDir = -Y_HOME_DIR; - stepperBackoutDir = INVERT_Y_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_Y_DIR, -)effectorBackoutDir; break; #endif #ifdef Z_MICROSTEPS @@ -1770,7 +1772,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(Z); phaseCurrent = stepperZ.get_microstep_counter(); effectorBackoutDir = -Z_HOME_DIR; - stepperBackoutDir = INVERT_Z_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_Z_DIR, -)effectorBackoutDir; break; #endif #ifdef I_MICROSTEPS @@ -1778,7 +1780,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(I); phaseCurrent = stepperI.get_microstep_counter(); effectorBackoutDir = -I_HOME_DIR; - stepperBackoutDir = INVERT_I_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_I_DIR, -)effectorBackoutDir; break; #endif #ifdef J_MICROSTEPS @@ -1786,7 +1788,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(J); phaseCurrent = stepperJ.get_microstep_counter(); effectorBackoutDir = -J_HOME_DIR; - stepperBackoutDir = INVERT_J_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_J_DIR, -)effectorBackoutDir; break; #endif #ifdef K_MICROSTEPS @@ -1794,7 +1796,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(K); phaseCurrent = stepperK.get_microstep_counter(); effectorBackoutDir = -K_HOME_DIR; - stepperBackoutDir = INVERT_K_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_K_DIR, -)effectorBackoutDir; break; #endif #ifdef U_MICROSTEPS @@ -1802,7 +1804,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(U); phaseCurrent = stepperU.get_microstep_counter(); effectorBackoutDir = -U_HOME_DIR; - stepperBackoutDir = INVERT_U_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_U_DIR, -)effectorBackoutDir; break; #endif #ifdef V_MICROSTEPS @@ -1810,7 +1812,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(V); phaseCurrent = stepperV.get_microstep_counter(); effectorBackoutDir = -V_HOME_DIR; - stepperBackoutDir = INVERT_V_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_V_DIR, -)effectorBackoutDir; break; #endif #ifdef W_MICROSTEPS @@ -1818,7 +1820,7 @@ void prepare_line_to_destination() { phasePerUStep = PHASE_PER_MICROSTEP(W); phaseCurrent = stepperW.get_microstep_counter(); effectorBackoutDir = -W_HOME_DIR; - stepperBackoutDir = INVERT_W_DIR ? effectorBackoutDir : -effectorBackoutDir; + stepperBackoutDir = IF_DISABLED(INVERT_W_DIR, -)effectorBackoutDir; break; #endif default: return; @@ -1877,17 +1879,8 @@ void prepare_line_to_destination() { || TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \ || TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \ )) - if (NUM_AXIS_GANG( - !_CAN_HOME(X), - && !_CAN_HOME(Y), - && !_CAN_HOME(Z), - && !_CAN_HOME(I), - && !_CAN_HOME(J), - && !_CAN_HOME(K), - && !_CAN_HOME(U), - && !_CAN_HOME(V), - && !_CAN_HOME(W)) - ) return; + #define _ANDCANT(N) && !_CAN_HOME(N) + if (true MAIN_AXIS_MAP(_ANDCANT)) return; #endif if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); @@ -2038,7 +2031,7 @@ void prepare_line_to_destination() { #if ENABLED(Z_MULTI_ENDSTOPS) if (axis == Z_AXIS) { - #if NUM_Z_STEPPER_DRIVERS == 2 + #if NUM_Z_STEPPERS == 2 const float adj = ABS(endstops.z2_endstop_adj); if (adj) { @@ -2056,13 +2049,13 @@ void prepare_line_to_destination() { adjustFunc_t lock[] = { stepper.set_z1_lock, stepper.set_z2_lock, stepper.set_z3_lock - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 , stepper.set_z4_lock #endif }; float adj[] = { 0, endstops.z2_endstop_adj, endstops.z3_endstop_adj - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 , endstops.z4_endstop_adj #endif }; @@ -2081,7 +2074,7 @@ void prepare_line_to_destination() { lock[1] = lock[2], adj[1] = adj[2]; lock[2] = tempLock, adj[2] = tempAdj; } - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 if (adj[3] < adj[2]) { tempLock = lock[2], tempAdj = adj[2]; lock[2] = lock[3], adj[2] = adj[3]; @@ -2106,14 +2099,14 @@ void prepare_line_to_destination() { // 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 + #if NUM_Z_STEPPERS >= 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 + #if NUM_Z_STEPPERS >= 4 (*lock[3])(true); do_homing_move(axis, adj[2] - adj[3]); #endif @@ -2126,7 +2119,7 @@ void prepare_line_to_destination() { stepper.set_z1_lock(false); stepper.set_z2_lock(false); stepper.set_z3_lock(false); - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 stepper.set_z4_lock(false); #endif diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 45dae5d6090a..ec478188772c 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -407,38 +407,41 @@ void restore_feedrate_and_scaling(); /** * Homing and Trusted Axes */ -typedef IF<(NUM_AXES > 8), uint16_t, uint8_t>::type linear_axis_bits_t; -constexpr linear_axis_bits_t linear_bits = _BV(NUM_AXES) - 1; +typedef IF<(NUM_AXES > 8), uint16_t, uint8_t>::type main_axes_bits_t; +constexpr main_axes_bits_t main_axes_mask = _BV(NUM_AXES) - 1; + +typedef IF<(NUM_AXES + EXTRUDERS > 8), uint16_t, uint8_t>::type e_axis_bits_t; +constexpr e_axis_bits_t e_axis_mask = (_BV(EXTRUDERS) - 1) << NUM_AXES; void set_axis_is_at_home(const AxisEnum axis); #if HAS_ENDSTOPS /** - * axis_homed + * axes_homed * Flags that each linear axis was homed. * XYZ on cartesian, ABC on delta, ABZ on SCARA. * - * axis_trusted + * axes_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; + extern main_axes_bits_t axes_homed, axes_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; } + main_axes_bits_t axes_should_home(main_axes_bits_t axes_mask=main_axes_mask); + bool homing_needed_error(main_axes_bits_t axes_mask=main_axes_mask); + inline void set_axis_unhomed(const AxisEnum axis) { CBI(axes_homed, axis); } + inline void set_axis_untrusted(const AxisEnum axis) { CBI(axes_trusted, axis); } + inline void set_all_unhomed() { axes_homed = axes_trusted = 0; } + inline void set_axis_homed(const AxisEnum axis) { SBI(axes_homed, axis); } + inline void set_axis_trusted(const AxisEnum axis) { SBI(axes_trusted, axis); } + inline void set_all_homed() { axes_homed = axes_trusted = main_axes_mask; } #else - constexpr linear_axis_bits_t axis_homed = linear_bits, axis_trusted = linear_bits; // Zero-endstop machines are always homed and trusted + constexpr main_axes_bits_t axes_homed = main_axes_mask, axes_trusted = main_axes_mask; // Zero-endstop machines are always homed and trusted inline void homeaxis(const AxisEnum axis) {} inline void set_axis_never_homed(const AxisEnum) {} - inline linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return 0; } - inline bool homing_needed_error(linear_axis_bits_t=linear_bits) { return false; } + inline main_axes_bits_t axes_should_home(main_axes_bits_t=main_axes_mask) { return 0; } + inline bool homing_needed_error(main_axes_bits_t=main_axes_mask) { return false; } inline void set_axis_unhomed(const AxisEnum axis) {} inline void set_axis_untrusted(const AxisEnum axis) {} inline void set_all_unhomed() {} @@ -447,13 +450,13 @@ void set_axis_is_at_home(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_was_homed(const AxisEnum axis) { return TEST(axes_homed, axis); } +inline bool axis_is_trusted(const AxisEnum axis) { return TEST(axes_trusted, axis); } inline bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } -inline bool no_axes_homed() { return !axis_homed; } -inline bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); } +inline bool no_axes_homed() { return !axes_homed; } +inline bool all_axes_homed() { return main_axes_mask == (axes_homed & main_axes_mask); } inline bool homing_needed() { return !all_axes_homed(); } -inline bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); } +inline bool all_axes_trusted() { return main_axes_mask == (axes_trusted & main_axes_mask); } void home_if_needed(const bool keeplev=false); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 31f03ce9283f..15084e7890a3 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -128,8 +128,13 @@ uint8_t Planner::delay_before_delivering; // This counter delays delivery planner_settings_t Planner::settings; // Initialized by settings.load() -#if ENABLED(LASER_POWER_INLINE) +/** + * Set up inline block variables + * Set laser_power_floor based on SPEED_POWER_MIN to pevent a zero power output state with LASER_POWER_TRAP + */ +#if ENABLED(LASER_FEATURE) laser_state_t Planner::laser_inline; // Current state for blocks + const uint8_t laser_power_floor = cutter.pct_to_ocr(SPEED_POWER_MIN); #endif uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2 @@ -739,7 +744,7 @@ block_t* Planner::get_current_block() { block_t * const block = &block_buffer[block_buffer_tail]; // No trapezoid calculated? Don't execute yet. - if (TEST(block->flag, BLOCK_BIT_RECALCULATE)) return nullptr; + if (block->flag.recalculate) return nullptr; // We can't be sure how long an active block will take, so don't count it. TERN_(HAS_WIRED_LCD, block_buffer_runtime_us -= block->segment_time_us); @@ -819,7 +824,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t // Store new block parameters block->accelerate_until = accelerate_steps; - block->decelerate_after = accelerate_steps + plateau_steps; + block->decelerate_after = block->step_event_count - decelerate_steps; block->initial_rate = initial_rate; #if ENABLED(S_CURVE_ACCELERATION) block->acceleration_time = acceleration_time; @@ -830,46 +835,52 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t #endif block->final_rate = final_rate; - /** - * Laser trapezoid calculations - * - * Approximate the trapezoid with the laser, incrementing the power every `entry_per` while accelerating - * and decrementing it every `exit_power_per` while decelerating, thus ensuring power is related to feedrate. - * - * LASER_POWER_INLINE_TRAPEZOID_CONT doesn't need this as it continuously approximates - * - * Note this may behave unreliably when running with S_CURVE_ACCELERATION - */ - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - if (block->laser.power > 0) { // No need to care if power == 0 - const uint8_t entry_power = block->laser.power * entry_factor; // Power on block entry - #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) - // Speedup power - const uint8_t entry_power_diff = block->laser.power - entry_power; - if (entry_power_diff) { - block->laser.entry_per = accelerate_steps / entry_power_diff; - block->laser.power_entry = entry_power; - } - else { - block->laser.entry_per = 0; - block->laser.power_entry = block->laser.power; - } - // Slowdown power - const uint8_t exit_power = block->laser.power * exit_factor, // Power on block entry - exit_power_diff = block->laser.power - exit_power; - if (exit_power_diff) { - block->laser.exit_per = (block->step_event_count - block->decelerate_after) / exit_power_diff; - block->laser.power_exit = exit_power; + #if ENABLED(LASER_POWER_TRAP) + /** + * Laser Trapezoid Calculations + * + * Approximate the trapezoid with the laser, incrementing the power every `trap_ramp_entry_incr` steps while accelerating, + * and decrementing the power every `trap_ramp_exit_decr` while decelerating, to keep power proportional to feedrate. + * Laser power trap will reduce the initial power to no less than the laser_power_floor value. Based on the number + * of calculated accel/decel steps the power is distributed over the trapezoid entry- and exit-ramp steps. + * + * trap_ramp_active_pwr - The active power is initially set at a reduced level factor of initial power / accel steps and + * will be additively incremented using a trap_ramp_entry_incr value for each accel step processed later in the stepper code. + * The trap_ramp_exit_decr value is calculated as power / decel steps and is also adjusted to no less than the power floor. + * + * If the power == 0 the inline mode variables need to be set to zero to prevent stepper processing. The method allows + * for simpler non-powered moves like G0 or G28. + * + * Laser Trap Power works for all Jerk and Curve modes; however Arc-based moves will have issues since the segments are + * usually too small. + */ + if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS) { + if (planner.laser_inline.status.isPowered && planner.laser_inline.status.isEnabled) { + if (block->laser.power > 0) { + NOLESS(block->laser.power, laser_power_floor); + block->laser.trap_ramp_active_pwr = (block->laser.power - laser_power_floor) * (initial_rate / float(block->nominal_rate)) + laser_power_floor; + block->laser.trap_ramp_entry_incr = (block->laser.power - block->laser.trap_ramp_active_pwr) / accelerate_steps; + float laser_pwr = block->laser.power * (final_rate / float(block->nominal_rate)); + NOLESS(laser_pwr, laser_power_floor); + block->laser.trap_ramp_exit_decr = (block->laser.power - laser_pwr) / decelerate_steps; + #if ENABLED(DEBUG_LASER_TRAP) + SERIAL_ECHO_MSG("lp:",block->laser.power); + SERIAL_ECHO_MSG("as:",accelerate_steps); + SERIAL_ECHO_MSG("ds:",decelerate_steps); + SERIAL_ECHO_MSG("p.trap:",block->laser.trap_ramp_active_pwr); + SERIAL_ECHO_MSG("p.incr:",block->laser.trap_ramp_entry_incr); + SERIAL_ECHO_MSG("p.decr:",block->laser.trap_ramp_exit_decr); + #endif } else { - block->laser.exit_per = 0; - block->laser.power_exit = block->laser.power; + block->laser.trap_ramp_active_pwr = 0; + block->laser.trap_ramp_entry_incr = 0; + block->laser.trap_ramp_exit_decr = 0; } - #else - block->laser.power_entry = entry_power; - #endif + + } } - #endif + #endif // LASER_POWER_TRAP } /* PLANNER SPEED DEFINITION @@ -945,7 +956,7 @@ void Planner::reverse_pass_kernel(block_t * const current, const block_t * const // Compute maximum entry speed decelerating over the current block from its exit speed. // If not at the maximum entry speed, or the previous block entry speed changed - if (current->entry_speed_sqr != max_entry_speed_sqr || (next && TEST(next->flag, BLOCK_BIT_RECALCULATE))) { + if (current->entry_speed_sqr != max_entry_speed_sqr || (next && next->flag.recalculate)) { // If nominal length true, max junction speed is guaranteed to be reached. // If a block can de/ac-celerate from nominal speed to zero within the length of the block, then @@ -955,14 +966,14 @@ void Planner::reverse_pass_kernel(block_t * const current, const block_t * const // the reverse and forward planners, the corresponding block junction speed will always be at the // the maximum junction speed and may always be ignored for any speed reduction checks. - const float new_entry_speed_sqr = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH) + const float new_entry_speed_sqr = current->flag.nominal_length ? max_entry_speed_sqr : _MIN(max_entry_speed_sqr, max_allowable_speed_sqr(-current->acceleration, next ? next->entry_speed_sqr : sq(float(MINIMUM_PLANNER_SPEED)), current->millimeters)); if (current->entry_speed_sqr != new_entry_speed_sqr) { // Need to recalculate the block speed - Mark it now, so the stepper // ISR does not consume the block before being recalculated - SBI(current->flag, BLOCK_BIT_RECALCULATE); + current->flag.recalculate = true; // But there is an inherent race condition here, as the block may have // become BUSY just before being marked RECALCULATE, so check for that! @@ -970,7 +981,7 @@ void Planner::reverse_pass_kernel(block_t * const current, const block_t * const // Block became busy. Clear the RECALCULATE flag (no point in // recalculating BUSY blocks). And don't set its speed, as it can't // be updated at this time. - CBI(current->flag, BLOCK_BIT_RECALCULATE); + current->flag.recalculate = false; } else { // Block is not BUSY so this is ahead of the Stepper ISR: @@ -1008,8 +1019,8 @@ void Planner::reverse_pass() { // Perform the reverse pass block_t *current = &block_buffer[block_index]; - // Only consider non sync-and-page blocks - if (!(current->flag & BLOCK_MASK_SYNC) && !IS_PAGE(current)) { + // Only process movement blocks + if (current->is_move()) { reverse_pass_kernel(current, next); next = current; } @@ -1038,8 +1049,7 @@ void Planner::forward_pass_kernel(const block_t * const previous, block_t * cons // change, adjust the entry speed accordingly. Entry speeds have already been reset, // maximized, and reverse-planned. If nominal length is set, max junction speed is // guaranteed to be reached. No need to recheck. - if (!TEST(previous->flag, BLOCK_BIT_NOMINAL_LENGTH) && - previous->entry_speed_sqr < current->entry_speed_sqr) { + if (!previous->flag.nominal_length && previous->entry_speed_sqr < current->entry_speed_sqr) { // Compute the maximum allowable speed const float new_entry_speed_sqr = max_allowable_speed_sqr(-previous->acceleration, previous->entry_speed_sqr, previous->millimeters); @@ -1049,7 +1059,7 @@ void Planner::forward_pass_kernel(const block_t * const previous, block_t * cons // Mark we need to recompute the trapezoidal shape, and do it now, // so the stepper ISR does not consume the block before being recalculated - SBI(current->flag, BLOCK_BIT_RECALCULATE); + current->flag.recalculate = true; // But there is an inherent race condition here, as the block maybe // became BUSY, just before it was marked as RECALCULATE, so check @@ -1058,7 +1068,7 @@ void Planner::forward_pass_kernel(const block_t * const previous, block_t * cons // Block became busy. Clear the RECALCULATE flag (no point in // recalculating BUSY blocks and don't set its speed, as it can't // be updated at this time. - CBI(current->flag, BLOCK_BIT_RECALCULATE); + current->flag.recalculate = false; } else { // Block is not BUSY, we won the race against the Stepper ISR: @@ -1103,8 +1113,8 @@ void Planner::forward_pass() { // Perform the forward pass block = &block_buffer[block_index]; - // Skip SYNC and page blocks - if (!(block->flag & BLOCK_MASK_SYNC) && !IS_PAGE(block)) { + // Only process movement blocks + if (block->is_move()) { // 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 @@ -1139,8 +1149,8 @@ void Planner::recalculate_trapezoids() { // Get the pointer to the block 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 (!(prev->flag & BLOCK_MASK_SYNC)) break; + // It the block is a move, we're done with this loop + if (prev->is_move()) break; // Examine the previous block. This and all following are SYNC blocks head_block_index = prev_index; @@ -1153,18 +1163,17 @@ void Planner::recalculate_trapezoids() { next = &block_buffer[block_index]; - // Skip sync and page blocks - if (!(next->flag & BLOCK_MASK_SYNC) && !IS_PAGE(next)) { + // Only process movement blocks + if (next->is_move()) { next_entry_speed = SQRT(next->entry_speed_sqr); if (block) { - // Recalculate if current block entry or exit junction speed has changed. - if (TEST(block->flag, BLOCK_BIT_RECALCULATE) || TEST(next->flag, BLOCK_BIT_RECALCULATE)) { - // Mark the current block as RECALCULATE, to protect it from the Stepper ISR running it. - // Note that due to the above condition, there's a chance the current block isn't marked as - // RECALCULATE yet, but the next one is. That's the reason for the following line. - SBI(block->flag, BLOCK_BIT_RECALCULATE); + // If the next block is marked to RECALCULATE, also mark the previously-fetched one + if (next->flag.recalculate) block->flag.recalculate = true; + + // Recalculate if current block entry or exit junction speed has changed. + if (block->flag.recalculate) { // But there is an inherent race condition here, as the block maybe // became BUSY, just before it was marked as RECALCULATE, so check @@ -1187,7 +1196,7 @@ void Planner::recalculate_trapezoids() { // Reset current only to ensure next trapezoid is computed - The // stepper is free to use the block from now on. - CBI(block->flag, BLOCK_BIT_RECALCULATE); + block->flag.recalculate = false; } } @@ -1204,7 +1213,7 @@ void Planner::recalculate_trapezoids() { // Mark the next(last) block as RECALCULATE, to prevent the Stepper ISR running it. // As the last block is always recalculated here, there is a chance the block isn't // marked as RECALCULATE yet. That's the reason for the following line. - SBI(next->flag, BLOCK_BIT_RECALCULATE); + block->flag.recalculate = true; // But there is an inherent race condition here, as the block maybe // became BUSY, just before it was marked as RECALCULATE, so check @@ -1226,7 +1235,7 @@ void Planner::recalculate_trapezoids() { // Reset next only to ensure its trapezoid is computed - The stepper is free to use // the block from now on. - CBI(next->flag, BLOCK_BIT_RECALCULATE); + next->flag.recalculate = false; } } @@ -1293,7 +1302,7 @@ void Planner::recalculate() { #endif // HAS_FAN /** - * Maintain fans, paste extruder pressure, + * Maintain fans, paste extruder pressure, spindle/laser power */ void Planner::check_axes_activity() { @@ -1303,7 +1312,7 @@ void Planner::check_axes_activity() { #if HAS_FAN && DISABLED(LASER_SYNCHRONOUS_M106_M107) #define HAS_TAIL_FAN_SPEED 1 - static uint8_t tail_fan_speed[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, 128); + static uint8_t tail_fan_speed[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, 13); bool fans_need_update = false; #endif @@ -1339,25 +1348,25 @@ void Planner::check_axes_activity() { #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]; + block_t * const bnext = &block_buffer[b]; 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, - if (TERN0(DISABLE_U, block->steps.u)) axis_active.u = true, - if (TERN0(DISABLE_V, block->steps.v)) axis_active.v = true, - if (TERN0(DISABLE_W, block->steps.w)) axis_active.w = true + if (TERN0(DISABLE_E, bnext->steps.e)) axis_active.e = true, + if (TERN0(DISABLE_X, bnext->steps.x)) axis_active.x = true, + if (TERN0(DISABLE_Y, bnext->steps.y)) axis_active.y = true, + if (TERN0(DISABLE_Z, bnext->steps.z)) axis_active.z = true, + if (TERN0(DISABLE_I, bnext->steps.i)) axis_active.i = true, + if (TERN0(DISABLE_J, bnext->steps.j)) axis_active.j = true, + if (TERN0(DISABLE_K, bnext->steps.k)) axis_active.k = true, + if (TERN0(DISABLE_U, bnext->steps.u)) axis_active.u = true, + if (TERN0(DISABLE_V, bnext->steps.v)) axis_active.v = true, + if (TERN0(DISABLE_W, bnext->steps.w)) axis_active.w = true ); } #endif } else { - TERN_(HAS_CUTTER, cutter.refresh()); + TERN_(HAS_CUTTER, if (cutter.cutter_mode == CUTTER_MODE_STANDARD) cutter.refresh()); #if HAS_TAIL_FAN_SPEED FANS_LOOP(i) { @@ -1448,14 +1457,14 @@ void Planner::check_axes_activity() { * currently in the planner. */ void Planner::autotemp_task() { - static float oldt = 0; + static float oldt = 0.0f; if (!autotemp_enabled) return; if (thermalManager.degTargetHotend(active_extruder) < autotemp_min - 2) return; // Below the min? - float high = 0.0; + float high = 0.0f; for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { - block_t *block = &block_buffer[b]; + const block_t * const block = &block_buffer[b]; if (NUM_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, || block->steps.i, || block->steps.j, || block->steps.k, || block->steps.u, || block->steps.v, || block->steps.w)) { const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec; NOLESS(high, se); @@ -1555,7 +1564,7 @@ void Planner::check_axes_activity() { 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(); + refresh_acceleration_rates(); } #endif @@ -1584,55 +1593,45 @@ void Planner::check_axes_activity() { #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) const float fade_scaling_factor = fade_scaling_factor_for_z(raw.z); - #elif DISABLED(MESH_BED_LEVELING) - constexpr float fade_scaling_factor = 1.0; + if (fade_scaling_factor) raw.z += fade_scaling_factor * bedlevel.get_z_correction(raw); + #else + raw.z += bedlevel.get_z_correction(raw); #endif - raw.z += ( - #if ENABLED(MESH_BED_LEVELING) - mbl.get_z(raw OPTARG(ENABLE_LEVELING_FADE_HEIGHT, fade_scaling_factor)) - #elif ENABLED(AUTO_BED_LEVELING_UBL) - fade_scaling_factor ? fade_scaling_factor * ubl.get_z_correction(raw) : 0.0 - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - fade_scaling_factor ? fade_scaling_factor * bbl.get_z_correction(raw) : 0.0 - #endif - ); + TERN_(MESH_BED_LEVELING, raw.z += bedlevel.get_z_offset()); #endif } void Planner::unapply_leveling(xyz_pos_t &raw) { + if (!leveling_active) return; - if (leveling_active) { - - #if ABL_PLANAR - - matrix_3x3 inverse = matrix_3x3::transpose(bed_level_matrix); + #if ABL_PLANAR - xy_pos_t d = raw - level_fulcrum; - inverse.apply_rotation_xyz(d.x, d.y, raw.z); - raw = d + level_fulcrum; + matrix_3x3 inverse = matrix_3x3::transpose(bed_level_matrix); - #elif HAS_MESH + xy_pos_t d = raw - level_fulcrum; + inverse.apply_rotation_xyz(d.x, d.y, raw.z); + raw = d + level_fulcrum; - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - const float fade_scaling_factor = fade_scaling_factor_for_z(raw.z); - #elif DISABLED(MESH_BED_LEVELING) - constexpr float fade_scaling_factor = 1.0; - #endif + #elif HAS_MESH - raw.z -= ( - #if ENABLED(MESH_BED_LEVELING) - mbl.get_z(raw OPTARG(ENABLE_LEVELING_FADE_HEIGHT, fade_scaling_factor)) - #elif ENABLED(AUTO_BED_LEVELING_UBL) - fade_scaling_factor ? fade_scaling_factor * ubl.get_z_correction(raw) : 0.0 - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - fade_scaling_factor ? fade_scaling_factor * bbl.get_z_correction(raw) : 0.0 - #endif - ); + const float z_correction = bedlevel.get_z_correction(raw), + z_full_fade = DIFF_TERN(MESH_BED_LEVELING, raw.z, bedlevel.get_z_offset()), + z_no_fade = z_full_fade - z_correction; + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + if (!z_fade_height || z_no_fade <= 0.0f) // Not fading or at bed level? + raw.z = z_no_fade; // Unapply full mesh Z. + else if (z_full_fade >= z_fade_height) // Above the fade height? + raw.z = z_full_fade; // Nothing more to unapply. + else // Within the fade zone? + raw.z = z_no_fade / (1.0f - z_correction * inverse_z_fade_height); // Unapply the faded Z offset + #else + raw.z = z_no_fade; #endif - } + + #endif } #endif // HAS_LEVELING @@ -1670,10 +1669,7 @@ void Planner::quick_stop() { // forced to empty, there's no risk the ISR will touch this. delay_before_delivering = BLOCK_DELAY_FOR_1ST_MOVE; - #if HAS_WIRED_LCD - // Clear the accumulated runtime - clear_block_buffer_runtime(); - #endif + TERN_(HAS_WIRED_LCD, clear_block_buffer_runtime()); // Clear the accumulated runtime // Make sure to drop any attempt of queuing moves for 1 second cleaning_buffer_counter = TEMP_TIMER_FREQUENCY; @@ -1805,11 +1801,12 @@ bool Planner::_buffer_steps(const xyze_long_t &target if (cleaning_buffer_counter) return false; // Fill the block with the specified movement - if (!_populate_block(block, false, target - OPTARG(HAS_POSITION_FLOAT, target_float) - OPTARG(HAS_DIST_MM_ARG, cart_dist_mm) - , fr_mm_s, extruder, millimeters - )) { + if (!_populate_block(block, target + OPTARG(HAS_POSITION_FLOAT, target_float) + OPTARG(HAS_DIST_MM_ARG, cart_dist_mm) + , fr_mm_s, extruder, millimeters + ) + ) { // Movement was not queued, probably because it was too short. // Simply accept that as movement queued and done return true; @@ -1836,17 +1833,24 @@ bool Planner::_buffer_steps(const xyze_long_t &target } /** - * Planner::_populate_block - * - * Fills a new linear movement in the block (in terms of steps). + * @brief Populate a block in preparation for insertion + * @details Populate the fields of a new linear movement block + * that will be added to the queue and processed soon + * by the Stepper ISR. * - * target - target position in steps units - * fr_mm_s - (target) speed of the move - * extruder - target extruder + * @param block A block to populate + * @param target Target position in steps units + * @param target_float Target position in native mm + * @param cart_dist_mm The pre-calculated move lengths for all axes, in mm + * @param fr_mm_s (target) speed of the move + * @param extruder target extruder + * @param millimeters A pre-calculated linear distance for the move, in mm, + * or 0.0 to have the distance calculated here. * - * Returns true if movement is acceptable, false otherwise + * @return true if movement is acceptable, false otherwise */ -bool Planner::_populate_block(block_t * const block, bool split_move, +bool Planner::_populate_block( + block_t * const block, const abce_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) @@ -1988,16 +1992,39 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif // Clear all flags, including the "busy" bit - block->flag = 0x00; + block->flag.clear(); // Set direction bits block->direction_bits = dm; - // Update block laser power - #if ENABLED(LASER_POWER_INLINE) - laser_inline.status.isPlanned = true; - block->laser.status = laser_inline.status; - block->laser.power = laser_inline.power; + /** + * Update block laser power + * For standard mode get the cutter.power value for processing, since it's + * only set by apply_power(). + */ + #if HAS_CUTTER + switch (cutter.cutter_mode) { + default: break; + + case CUTTER_MODE_STANDARD: block->cutter_power = cutter.power; break; + + #if ENABLED(LASER_FEATURE) + /** + * For inline mode get the laser_inline variables, including power and status. + * Dynamic mode only needs to update if the feedrate has changed, since it's + * calculated from the current feedrate and power level. + */ + case CUTTER_MODE_CONTINUOUS: + block->laser.power = laser_inline.power; + block->laser.status = laser_inline.status; + break; + + case CUTTER_MODE_DYNAMIC: + if (cutter.laser_feedrate_changed()) // Only process changes in rate + block->laser.power = laser_inline.power = cutter.calc_dynamic_power(); + break; + #endif + } #endif // Number of steps for each axis @@ -2130,8 +2157,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, ); #elif ENABLED(FOAMCUTTER_XYUV) #if HAS_J_AXIS - // Special 5 axis kinematics. Return the largest distance move from either X/Y or I/J plane - _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j)) + // Special 5 axis kinematics. Return the largest distance move from either X/Y or I/J plane + _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j)) #else // Foamcutter with only two axes (XY) sq(steps_dist_mm.x) + sq(steps_dist_mm.y) #endif @@ -2198,7 +2225,6 @@ bool Planner::_populate_block(block_t * const block, bool split_move, TERN_(MIXING_EXTRUDER, mixer.populate_block(block->b_color)); - TERN_(HAS_CUTTER, block->cutter_power = cutter.power); #if HAS_FAN FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; @@ -2561,7 +2587,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->acceleration_steps_per_s2 = accel; block->acceleration = accel / steps_per_mm; #if DISABLED(S_CURVE_ACCELERATION) - block->acceleration_rate = (uint32_t)(accel * (sq(4096.0f) / (STEPPER_TIMER_RATE))); + block->acceleration_rate = (uint32_t)(accel * (float(1UL << 24) / (STEPPER_TIMER_RATE))); #endif #if ENABLED(LIN_ADVANCE) if (block->use_advance_lead) { @@ -2882,9 +2908,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED. const float v_allowable_sqr = max_allowable_speed_sqr(-block->acceleration, sq(float(MINIMUM_PLANNER_SPEED)), block->millimeters); - // If we are trying to add a split block, start with the - // max. allowed speed to avoid an interrupted first move. - block->entry_speed_sqr = !split_move ? sq(float(MINIMUM_PLANNER_SPEED)) : _MIN(vmax_junction_sqr, v_allowable_sqr); + // Start with the minimum allowed speed + block->entry_speed_sqr = sq(float(MINIMUM_PLANNER_SPEED)); // Initialize planner efficiency flags // Set flag if block will always reach maximum junction speed regardless of entry/exit speeds. @@ -2894,7 +2919,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // block nominal speed limits both the current and next maximum junction speeds. Hence, in both // the reverse and forward planners, the corresponding block junction speed will always be at the // the maximum junction speed and may always be ignored for any speed reduction checks. - block->flag |= block->nominal_speed_sqr <= v_allowable_sqr ? BLOCK_FLAG_RECALCULATE | BLOCK_FLAG_NOMINAL_LENGTH : BLOCK_FLAG_RECALCULATE; + block->flag.set_nominal(block->nominal_speed_sqr <= v_allowable_sqr); // Update previous path unit_vector and nominal speed previous_speed = current_speed; @@ -2916,13 +2941,12 @@ 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, - * or in case of LASER_SYNCHRONOUS_M106_M107 the fan PWM + * Add a block to the buffer that just updates the position + * @param sync_flag BLOCK_FLAG_SYNC_FANS & BLOCK_FLAG_LASER_PWR + * Supports LASER_SYNCHRONOUS_M106_M107 and LASER_POWER_SYNC power sync block buffer queueing. */ -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 + +void Planner::buffer_sync_block(const BlockFlagBit sync_flag/*=BLOCK_BIT_SYNC_POSITION*/) { // Wait for the next available block uint8_t next_buffer_head; @@ -2930,8 +2954,7 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_ // Clear block memset(block, 0, sizeof(block_t)); - - block->flag = sync_flag; + block->flag.apply(sync_flag); block->position = position; #if ENABLED(BACKLASH_COMPENSATION) @@ -2942,6 +2965,12 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_ FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif + /** + * M3-based power setting can be processed inline with a laser power sync block. + * During active moves cutter.power is processed immediately, otherwise on the next move. + */ + TERN_(LASER_POWER_SYNC, block->laser.power = cutter.power); + // 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 @@ -3126,7 +3155,7 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons inverse_kinematics(machine); #if ENABLED(SCARA_FEEDRATE_SCALING) - // For SCARA scale the feed rate from mm/s to degrees/s + // For SCARA scale the feedrate from mm/s to degrees/s // i.e., Complete the angular vector in the given time. const float duration_recip = inv_duration ?: fr_mm_s / mm; const xyz_pos_t diff = delta - position_float; @@ -3156,7 +3185,7 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons uint8_t next_buffer_head; block_t * const block = get_next_free_block(next_buffer_head); - block->flag = BLOCK_FLAG_IS_PAGE; + block->flag.reset(BLOCK_BIT_PAGE); #if HAS_FAN FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; @@ -3231,7 +3260,7 @@ void Planner::set_machine_position_mm(const abce_pos_t &abce) { if (has_blocks_queued()) { //previous_nominal_speed_sqr = 0.0; // Reset planner junction speeds. Assume start from rest. //previous_speed.reset(); - buffer_sync_block(); + buffer_sync_block(BLOCK_BIT_SYNC_POSITION); } else { #if ENABLED(BACKLASH_COMPENSATION) @@ -3272,7 +3301,7 @@ void Planner::set_position_mm(const xyze_pos_t &xyze) { TERN_(IS_KINEMATIC, TERN_(HAS_EXTRUDERS, position_cart.e = e)); if (has_blocks_queued()) - buffer_sync_block(); + buffer_sync_block(BLOCK_BIT_SYNC_POSITION); else stepper.set_axis_position(E_AXIS, position.e); } @@ -3280,7 +3309,7 @@ void Planner::set_position_mm(const xyze_pos_t &xyze) { #endif // Recalculate the steps/s^2 acceleration rates, based on the mm/s^2 -void Planner::reset_acceleration_rates() { +void Planner::refresh_acceleration_rates() { uint32_t highest_rate = 1; LOOP_DISTINCT_AXES(i) { max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i]; @@ -3298,7 +3327,7 @@ void Planner::reset_acceleration_rates() { void Planner::refresh_positioning() { LOOP_DISTINCT_AXES(i) mm_per_step[i] = 1.0f / settings.axis_steps_per_mm[i]; set_position_mm(current_position); - reset_acceleration_rates(); + refresh_acceleration_rates(); } // Apply limits to a variable and give a warning if the value was out of range @@ -3317,7 +3346,7 @@ inline void limit_and_warn(float &val, const AxisEnum axis, PGM_P const setting_ /** * 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. + * Calls refresh_acceleration_rates to precalculate planner terms in steps. * * This hard limit is applied as a block is being added to the planner queue. */ @@ -3335,7 +3364,7 @@ void Planner::set_max_acceleration(const AxisEnum axis, float inMaxAccelMMS2) { 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(); + refresh_acceleration_rates(); } /** diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index afcc5a1566cb..e0aa89ab7228 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -70,9 +70,6 @@ #if ENABLED(DIRECT_STEPPING) #include "../feature/direct_stepping.h" - #define IS_PAGE(B) TEST(B->flag, BLOCK_BIT_IS_PAGE) -#else - #define IS_PAGE(B) false #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) @@ -92,7 +89,10 @@ #define HAS_DIST_MM_ARG 1 #endif -enum BlockFlagBit : char { +/** + * Planner block flags as boolean bit fields + */ +enum BlockFlagBit { // Recalculate trapezoids on entry junction. For optimization. BLOCK_BIT_RECALCULATE, @@ -108,50 +108,72 @@ enum BlockFlagBit : char { BLOCK_BIT_SYNC_POSITION // Direct stepping page - #if ENABLED(DIRECT_STEPPING) - , BLOCK_BIT_IS_PAGE - #endif + OPTARG(DIRECT_STEPPING, BLOCK_BIT_PAGE) + // Sync the fan speeds from the block - #if ENABLED(LASER_SYNCHRONOUS_M106_M107) - , BLOCK_BIT_SYNC_FANS - #endif -}; + OPTARG(LASER_SYNCHRONOUS_M106_M107, BLOCK_BIT_SYNC_FANS) -enum BlockFlag : char { - BLOCK_FLAG_RECALCULATE = _BV(BLOCK_BIT_RECALCULATE) - , BLOCK_FLAG_NOMINAL_LENGTH = _BV(BLOCK_BIT_NOMINAL_LENGTH) - , BLOCK_FLAG_CONTINUED = _BV(BLOCK_BIT_CONTINUED) - , BLOCK_FLAG_SYNC_POSITION = _BV(BLOCK_BIT_SYNC_POSITION) - #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 + // Sync laser power from a queued block + OPTARG(LASER_POWER_SYNC, BLOCK_BIT_LASER_PWR) }; -#define BLOCK_MASK_SYNC ( BLOCK_FLAG_SYNC_POSITION | TERN0(LASER_SYNCHRONOUS_M106_M107, BLOCK_FLAG_SYNC_FANS) ) +/** + * Planner block flags as boolean bit fields + */ +typedef struct { + union { + uint8_t bits; + + struct { + bool recalculate:1; -#if ENABLED(LASER_POWER_INLINE) + bool nominal_length:1; + + bool continued:1; + + bool sync_position:1; + + #if ENABLED(DIRECT_STEPPING) + bool page:1; + #endif + + #if ENABLED(LASER_SYNCHRONOUS_M106_M107) + bool sync_fans:1; + #endif + + #if ENABLED(LASER_POWER_SYNC) + bool sync_laser_pwr:1; + #endif + }; + }; + + void clear() volatile { bits = 0; } + void apply(const uint8_t f) volatile { bits |= f; } + void apply(const BlockFlagBit b) volatile { SBI(bits, b); } + void reset(const BlockFlagBit b) volatile { bits = _BV(b); } + void set_nominal(const bool n) volatile { recalculate = true; if (n) nominal_length = true; } + +} block_flags_t; + +#if ENABLED(LASER_FEATURE) typedef struct { - bool isPlanned:1; - bool isEnabled:1; + bool isEnabled:1; // Set to engage the inline laser power output. bool dir:1; - bool Reserved:6; + bool isPowered:1; // Set on any parsed G1, G2, G3, or G5 powered move, cleared on G0 and G28. + bool isSyncPower:1; // Set on a M3 sync based set laser power, used to determine active trap power + bool Reserved:4; } power_status_t; typedef struct { - power_status_t status; // See planner settings for meaning - uint8_t power; // Ditto; When in trapezoid mode this is nominal power - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - uint8_t power_entry; // Entry power for the laser - #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) - uint8_t power_exit; // Exit power for the laser - uint32_t entry_per, // Steps per power increment (to avoid floats in stepper calcs) - exit_per; // Steps per power decrement - #endif + power_status_t status; // See planner settings for meaning + uint8_t power; // Ditto; When in trapezoid mode this is nominal power + + #if ENABLED(LASER_POWER_TRAP) + float trap_ramp_active_pwr; // Laser power level during active trapezoid smoothing + float trap_ramp_entry_incr; // Acceleration per step laser power increment (trap entry) + float trap_ramp_exit_decr; // Deceleration per step laser power decrement (trap exit) #endif } block_laser_t; @@ -163,12 +185,18 @@ enum BlockFlag : char { * A single entry in the planner buffer. * Tracks linear movement over multiple axes. * - * The "nominal" values are as-specified by gcode, and + * The "nominal" values are as-specified by G-code, and * may never actually be reached due to acceleration limits. */ typedef struct block_t { - volatile uint8_t flag; // Block flags (See BlockFlag enum above) - Modified by ISR and main thread! + volatile block_flags_t flag; // Block flags + + volatile bool is_fan_sync() { return TERN0(LASER_SYNCHRONOUS_M106_M107, flag.sync_fans); } + volatile bool is_pwr_sync() { return TERN0(LASER_POWER_SYNC, flag.sync_laser_pwr); } + volatile bool is_sync() { return flag.sync_position || is_fan_sync() || is_pwr_sync(); } + volatile bool is_page() { return TERN0(DIRECT_STEPPING, flag.page); } + volatile bool is_move() { return !(is_sync() || is_page()); } // Fields used by the motion planner to manage acceleration float nominal_speed_sqr, // The nominal speed for this block in (mm/sec)^2 @@ -248,7 +276,7 @@ typedef struct block_t { xyze_pos_t start_position; #endif - #if ENABLED(LASER_POWER_INLINE) + #if ENABLED(LASER_FEATURE) block_laser_t laser; #endif @@ -260,7 +288,7 @@ typedef struct block_t { #define BLOCK_MOD(n) ((n)&(BLOCK_BUFFER_SIZE-1)) -#if ENABLED(LASER_POWER_INLINE) +#if ENABLED(LASER_FEATURE) typedef struct { /** * Laser status flags @@ -269,11 +297,10 @@ typedef struct block_t { /** * Laser power: 0 or 255 in case of PWM-less laser, * or the OCR (oscillator count register) value; - * * Using OCR instead of raw power, because it avoids * floating point operations during the move loop. */ - uint8_t power; + volatile uint8_t power; } laser_state_t; #endif @@ -375,7 +402,7 @@ class Planner { static planner_settings_t settings; - #if ENABLED(LASER_POWER_INLINE) + #if ENABLED(LASER_FEATURE) static laser_state_t laser_inline; #endif @@ -412,7 +439,7 @@ class Planner { /** * The current position of the tool in absolute steps - * Recalculated if any axis_steps_per_mm are changed by gcode + * Recalculated if any axis_steps_per_mm are changed by G-code */ static xyze_long_t position; @@ -492,7 +519,7 @@ class Planner { */ // Recalculate steps/s^2 accelerations based on mm/s^2 settings - static void reset_acceleration_rates(); + static void refresh_acceleration_rates(); /** * Recalculate 'position' and 'mm_per_step'. @@ -736,18 +763,23 @@ class Planner { ); /** - * Planner::_populate_block + * @brief Populate a block in preparation for insertion + * @details Populate the fields of a new linear movement block + * that will be added to the queue and processed soon + * by the Stepper ISR. * - * Fills a new linear movement in the block (in terms of steps). + * @param block A block to populate + * @param target Target position in steps units + * @param target_float Target position in native mm + * @param cart_dist_mm The pre-calculated move lengths for all axes, in mm + * @param fr_mm_s (target) speed of the move + * @param extruder target extruder + * @param millimeters A pre-calculated linear distance for the move, in mm, + * or 0.0 to have the distance calculated here. * - * target - target position in steps units - * fr_mm_s - (target) speed of the move - * extruder - target extruder - * millimeters - the length of the movement, if known - * - * Returns true is movement is acceptable, false otherwise + * @return true if movement is acceptable, false otherwise */ - static bool _populate_block(block_t * const block, bool split_move, const xyze_long_t &target + static bool _populate_block(block_t * const block, 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 @@ -755,12 +787,11 @@ class Planner { /** * Planner::buffer_sync_block - * Add a block to the buffer that just updates the position or in - * case of LASER_SYNCHRONOUS_M106_M107 the fan pwm + * Add a block to the buffer that just updates the position + * @param sync_flag sets a condition bit to process additional items + * such as sync fan pwm or sync M3/M4 laser power into a queued block */ - static void buffer_sync_block( - TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_flag=BLOCK_FLAG_SYNC_POSITION) - ); + static void buffer_sync_block(const BlockFlagBit flag=BLOCK_BIT_SYNC_POSITION); #if IS_KINEMATIC private: @@ -1022,7 +1053,7 @@ class Planner { return limit_value; } - #endif // !CLASSIC_JERK + #endif // HAS_JUNCTION_DEVIATION }; #define PLANNER_XY_FEEDRATE() _MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]) diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index fa7e16a387e6..93b118f33054 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -123,7 +123,7 @@ void cubic_b_spline( for (float t = 0; t < 1;) { - thermalManager.manage_heater(); + thermalManager.task(); millis_t now = millis(); if (ELAPSED(now, next_idle_ms)) { next_idle_ms = now + 200UL; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 30cd8d5162b9..afe5ba7a7416 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -48,6 +48,11 @@ #include "delta.h" #endif +#if ENABLED(SENSORLESS_PROBING) + abc_float_t offset_sensorless_adj{0}; + float largest_sensorless_adj = 0; +#endif + #if ANY(HAS_QUIET_PROBING, USE_SENSORLESS) #include "stepper/indirection.h" #if BOTH(HAS_QUIET_PROBING, PROBING_ESTEPPERS_OFF) @@ -103,7 +108,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #endif #if ENABLED(SENSORLESS_PROBING) - Probe::sense_bool_t Probe::test_sensitivity; + Probe::sense_bool_t Probe::test_sensitivity = { true, true, true }; #endif #if ENABLED(Z_PROBE_SLED) @@ -259,7 +264,57 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #endif } -#endif // Z_PROBE_ALLEN_KEY +#elif ENABLED(MAG_MOUNTED_PROBE) + + typedef struct { float fr_mm_min; xyz_pos_t where; } mag_probe_move_t; + + inline void run_deploy_moves_script() { + #ifdef MAG_MOUNTED_DEPLOY_1 + constexpr mag_probe_move_t deploy_1 = MAG_MOUNTED_DEPLOY_1; + do_blocking_move_to(deploy_1.where, MMM_TO_MMS(deploy_1.fr_mm_min)); + #endif + #ifdef MAG_MOUNTED_DEPLOY_2 + constexpr mag_probe_move_t deploy_2 = MAG_MOUNTED_DEPLOY_2; + do_blocking_move_to(deploy_2.where, MMM_TO_MMS(deploy_2.fr_mm_min)); + #endif + #ifdef MAG_MOUNTED_DEPLOY_3 + constexpr mag_probe_move_t deploy_3 = MAG_MOUNTED_DEPLOY_3; + do_blocking_move_to(deploy_3.where, MMM_TO_MMS(deploy_3.fr_mm_min)); + #endif + #ifdef MAG_MOUNTED_DEPLOY_4 + constexpr mag_probe_move_t deploy_4 = MAG_MOUNTED_DEPLOY_4; + do_blocking_move_to(deploy_4.where, MMM_TO_MMS(deploy_4.fr_mm_min)); + #endif + #ifdef MAG_MOUNTED_DEPLOY_5 + constexpr mag_probe_move_t deploy_5 = MAG_MOUNTED_DEPLOY_5; + do_blocking_move_to(deploy_5.where, MMM_TO_MMS(deploy_5.fr_mm_min)); + #endif + } + + inline void run_stow_moves_script() { + #ifdef MAG_MOUNTED_STOW_1 + constexpr mag_probe_move_t stow_1 = MAG_MOUNTED_STOW_1; + do_blocking_move_to(stow_1.where, MMM_TO_MMS(stow_1.fr_mm_min)); + #endif + #ifdef MAG_MOUNTED_STOW_2 + constexpr mag_probe_move_t stow_2 = MAG_MOUNTED_STOW_2; + do_blocking_move_to(stow_2.where, MMM_TO_MMS(stow_2.fr_mm_min)); + #endif + #ifdef MAG_MOUNTED_STOW_3 + constexpr mag_probe_move_t stow_3 = MAG_MOUNTED_STOW_3; + do_blocking_move_to(stow_3.where, MMM_TO_MMS(stow_3.fr_mm_min)); + #endif + #ifdef MAG_MOUNTED_STOW_4 + constexpr mag_probe_move_t stow_4 = MAG_MOUNTED_STOW_4; + do_blocking_move_to(stow_4.where, MMM_TO_MMS(stow_4.fr_mm_min)); + #endif + #ifdef MAG_MOUNTED_STOW_5 + constexpr mag_probe_move_t stow_5 = MAG_MOUNTED_STOW_5; + do_blocking_move_to(stow_5.where, MMM_TO_MMS(stow_5.fr_mm_min)); + #endif + } + +#endif // MAG_MOUNTED_PROBE #if HAS_QUIET_PROBING @@ -274,14 +329,14 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #if ENABLED(PROBING_STEPPERS_OFF) && DISABLED(DELTA) static uint8_t old_trusted; if (dopause) { - old_trusted = axis_trusted; + old_trusted = axes_trusted; stepper.disable_axis(X_AXIS); stepper.disable_axis(Y_AXIS); } else { if (TEST(old_trusted, X_AXIS)) stepper.enable_axis(X_AXIS); if (TEST(old_trusted, Y_AXIS)) stepper.enable_axis(Y_AXIS); - axis_trusted = old_trusted; + axes_trusted = old_trusted; } #endif if (dopause) safe_delay(_MAX(DELAY_BEFORE_PROBING, 25)); @@ -343,9 +398,9 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #elif HAS_Z_SERVO_PROBE - MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][deploy ? 0 : 1]); + servo[Z_PROBE_SERVO_NR].move(servo_angles[Z_PROBE_SERVO_NR][deploy ? 0 : 1]); - #elif EITHER(TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY) + #elif ANY(TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, MAG_MOUNTED_PROBE) deploy ? run_deploy_moves_script() : run_stow_moves_script(); @@ -531,12 +586,12 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if ENABLED(SENSORLESS_PROBING) sensorless_t stealth_states { false }; #if HAS_DELTA_SENSORLESS_PROBING - if (test_sensitivity.x) stealth_states.x = tmc_enable_stallguard(stepperX); // Delta watches all DIAG pins for a stall + if (test_sensitivity.x) stealth_states.x = tmc_enable_stallguard(stepperX); // Delta watches all DIAG pins for a stall if (test_sensitivity.y) stealth_states.y = tmc_enable_stallguard(stepperY); #endif - if (test_sensitivity.z) stealth_states.z = tmc_enable_stallguard(stepperZ); // All machines will check Z-DIAG for stall + if (test_sensitivity.z) stealth_states.z = tmc_enable_stallguard(stepperZ); // All machines will check Z-DIAG for stall + endstops.set_homing_current(true); // The "homing" current also applies to probing endstops.enable(true); - set_homing_current(true); // The "homing" current also applies to probing #endif TERN_(HAS_QUIET_PROBING, set_probing_paused(true)); @@ -553,6 +608,11 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #endif ; + // Offset sensorless probing + #if HAS_DELTA_SENSORLESS_PROBING + if (probe_triggered) probe.refresh_largest_sensorless_adj(); + #endif + TERN_(HAS_QUIET_PROBING, set_probing_paused(false)); // Re-enable stealthChop if used. Disable diag1 pin on driver. @@ -563,7 +623,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { if (test_sensitivity.y) tmc_disable_stallguard(stepperY, stealth_states.y); #endif if (test_sensitivity.z) tmc_disable_stallguard(stepperZ, stealth_states.z); - set_homing_current(false); + endstops.set_homing_current(false); #endif #if ENABLED(BLTOUCH) @@ -666,8 +726,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { if (try_to_probe(PSTR("FAST"), z_probe_low_point, z_probe_fast_mm_s, sanity_check, Z_CLEARANCE_BETWEEN_PROBES) ) return NAN; - const float first_probe_z = current_position.z; - + const float first_probe_z = DIFF_TERN(HAS_DELTA_SENSORLESS_PROBING, current_position.z, largest_sensorless_adj); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("1st Probe Z:", first_probe_z); // Raise to give the probe clearance @@ -709,7 +768,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { TERN_(MEASURE_BACKLASH_WHEN_PROBING, backlash.measure_with_probe()); - const float z = current_position.z; + const float z = DIFF_TERN(HAS_DELTA_SENSORLESS_PROBING, current_position.z, largest_sensorless_adj); #if EXTRA_PROBING > 0 // Insert Z measurement into probes[]. Keep it sorted ascending. @@ -760,7 +819,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { #elif TOTAL_PROBING == 2 - const float z2 = current_position.z; + const float z2 = DIFF_TERN(HAS_DELTA_SENSORLESS_PROBING, current_position.z, largest_sensorless_adj); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("2nd Probe Z:", z2, " Discrepancy:", first_probe_z - z2); @@ -843,7 +902,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai SERIAL_ERROR_MSG(STR_ERR_PROBING_FAILED); #endif } - + DEBUG_ECHOLNPGM("measured_z: ", measured_z); return measured_z; } @@ -863,95 +922,38 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai #endif // HAS_Z_SERVO_PROBE -#if USE_SENSORLESS - - sensorless_t stealth_states { false }; - - /** - * Disable stealthChop if used. Enable diag1 pin on driver. - */ - void Probe::enable_stallguard_diag1() { - #if ENABLED(SENSORLESS_PROBING) - #if HAS_DELTA_SENSORLESS_PROBING - 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 - } +#if HAS_DELTA_SENSORLESS_PROBING /** - * Re-enable stealthChop if used. Disable diag1 pin on driver. + * Set the sensorless Z offset */ - void Probe::disable_stallguard_diag1() { - #if ENABLED(SENSORLESS_PROBING) - endstops.not_homing(); - #if HAS_DELTA_SENSORLESS_PROBING - tmc_disable_stallguard(stepperX, stealth_states.x); - tmc_disable_stallguard(stepperY, stealth_states.y); - #endif - tmc_disable_stallguard(stepperZ, stealth_states.z); - #endif + void Probe::set_offset_sensorless_adj(const_float_t sz) { + DEBUG_SECTION(pso, "Probe::set_offset_sensorless_adj", true); + if (test_sensitivity.x) offset_sensorless_adj.a = sz; + if (test_sensitivity.y) offset_sensorless_adj.b = sz; + if (test_sensitivity.z) offset_sensorless_adj.c = sz; } /** - * Change the current in the TMC drivers to N##_CURRENT_HOME. And we save the current configuration of each TMC driver. + * Refresh largest_sensorless_adj based on triggered endstops */ - 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) || HAS_CURRENT_HOME(I) || HAS_CURRENT_HOME(J) || HAS_CURRENT_HOME(K) || HAS_CURRENT_HOME(U) || HAS_CURRENT_HOME(V) || HAS_CURRENT_HOME(W) - #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_ECHOLNPGM(" 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 + void Probe::refresh_largest_sensorless_adj() { + DEBUG_SECTION(rso, "Probe::refresh_largest_sensorless_adj", true); + largest_sensorless_adj = -3; // A reference away from any real probe height + if (TEST(endstops.state(), X_MAX)) { + NOLESS(largest_sensorless_adj, offset_sensorless_adj.a); + DEBUG_ECHOLNPGM("Endstop_X: ", largest_sensorless_adj, " TowerX"); + } + if (TEST(endstops.state(), Y_MAX)) { + NOLESS(largest_sensorless_adj, offset_sensorless_adj.b); + DEBUG_ECHOLNPGM("Endstop_Y: ", largest_sensorless_adj, " TowerY"); + } + if (TEST(endstops.state(), Z_MAX)) { + NOLESS(largest_sensorless_adj, offset_sensorless_adj.c); + DEBUG_ECHOLNPGM("Endstop_Z: ", largest_sensorless_adj, " TowerZ"); + } } -#endif // SENSORLESS_PROBING || SENSORLESS_HOMING +#endif #endif // HAS_BED_PROBE diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 6185196320c8..1bcbc6564241 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -62,11 +62,17 @@ #endif #endif +#if ENABLED(SENSORLESS_PROBING) + extern abc_float_t offset_sensorless_adj; +#endif + class Probe { public: #if ENABLED(SENSORLESS_PROBING) - typedef struct { bool x:1, y:1, z:1; } sense_bool_t; + typedef struct { + bool x:1, y:1, z:1; + } sense_bool_t; static sense_bool_t test_sensitivity; #endif @@ -296,10 +302,9 @@ class Probe { #endif // Basic functions for Sensorless Homing and Probing - #if USE_SENSORLESS - static void enable_stallguard_diag1(); - static void disable_stallguard_diag1(); - static void set_homing_current(const bool onoff); + #if HAS_DELTA_SENSORLESS_PROBING + static void set_offset_sensorless_adj(const_float_t sz); + static void refresh_largest_sensorless_adj(); #endif private: diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 96d5ba9da837..2782be1f2bd9 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -39,19 +39,19 @@ hal_servo_t servo[NUM_SERVOS]; void servo_init() { #if NUM_SERVOS >= 1 && HAS_SERVO_0 servo[0].attach(SERVO0_PIN); - DETACH_SERVO(0); // Just set up the pin. We don't have a position yet. Don't move to a random position. + servo[0].detach(); // Just set up the pin. We don't have a position yet. Don't move to a random position. #endif #if NUM_SERVOS >= 2 && HAS_SERVO_1 servo[1].attach(SERVO1_PIN); - DETACH_SERVO(1); + servo[1].detach(); #endif #if NUM_SERVOS >= 3 && HAS_SERVO_2 servo[2].attach(SERVO2_PIN); - DETACH_SERVO(2); + servo[2].detach(); #endif #if NUM_SERVOS >= 4 && HAS_SERVO_3 servo[3].attach(SERVO3_PIN); - DETACH_SERVO(3); + servo[3].detach(); #endif } diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index cd55a317a275..2ed992aa03f7 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -103,14 +103,11 @@ }; #if HAS_Z_SERVO_PROBE - #define DEPLOY_Z_SERVO() MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][0]) - #define STOW_Z_SERVO() MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][1]) + #define DEPLOY_Z_SERVO() servo[Z_PROBE_SERVO_NR].move(servo_angles[Z_PROBE_SERVO_NR][0]) + #define STOW_Z_SERVO() servo[Z_PROBE_SERVO_NR].move(servo_angles[Z_PROBE_SERVO_NR][1]) #endif #endif // HAS_SERVO_ANGLES -#define MOVE_SERVO(I, P) servo[I].move(P) -#define DETACH_SERVO(I) servo[I].detach() - extern hal_servo_t servo[NUM_SERVOS]; void servo_init(); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index a9737e5ed3c3..d21dc92c67c4 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -76,8 +76,6 @@ #include "../lcd/extui/ui_api.h" #elif ENABLED(DWIN_LCD_PROUI) #include "../lcd/e3v2/proui/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "../lcd/e3v2/jyersui/dwin.h" #endif #if ENABLED(HOST_PROMPT_SUPPORT) @@ -180,9 +178,9 @@ #define _EN_ITEM(N) , E##N #define _EN1_ITEM(N) , E##N:1 -typedef struct { uint16_t NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } per_stepper_uint16_t; -typedef struct { uint32_t NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } per_stepper_uint32_t; -typedef struct { int16_t NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4; } mot_stepper_int16_t; +typedef struct { uint16_t MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } per_stepper_uint16_t; +typedef struct { uint32_t MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } per_stepper_uint32_t; +typedef struct { int16_t MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4; } mot_stepper_int16_t; typedef struct { bool NUM_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, W:1), X2:1, Y2:1, Z2:1, Z3:1, Z4:1 REPEAT(E_STEPPERS, _EN1_ITEM); } per_stepper_bool_t; #undef _EN_ITEM @@ -247,9 +245,9 @@ typedef struct SettingsDataStruct { // // MESH_BED_LEVELING // - float mbl_z_offset; // mbl.z_offset + float mbl_z_offset; // bedlevel.z_offset uint8_t mesh_num_x, mesh_num_y; // GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - float mbl_z_values[TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_X, 3)] // mbl.z_values + float mbl_z_values[TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_X, 3)] // bedlevel.z_values [TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_Y, 3)]; // @@ -287,7 +285,7 @@ typedef struct SettingsDataStruct { // AUTO_BED_LEVELING_UBL // bool planner_leveling_active; // M420 S planner.leveling_active - int8_t ubl_storage_slot; // ubl.storage_slot + int8_t ubl_storage_slot; // bedlevel.storage_slot // // SERVO_ANGLES @@ -347,9 +345,9 @@ typedef struct SettingsDataStruct { // Z_STEPPER_AUTO_ALIGN, HAS_Z_STEPPER_ALIGN_STEPPER_XY // #if ENABLED(Z_STEPPER_AUTO_ALIGN) - xy_pos_t z_stepper_align_xy[NUM_Z_STEPPER_DRIVERS]; // M422 S X Y + xy_pos_t z_stepper_align_xy[NUM_Z_STEPPERS]; // M422 S X Y #if HAS_Z_STEPPER_ALIGN_STEPPER_XY - xy_pos_t z_stepper_align_stepper_xy[NUM_Z_STEPPER_DRIVERS]; // M422 W X Y + xy_pos_t z_stepper_align_stepper_xy[NUM_Z_STEPPERS]; // M422 W X Y #endif #endif @@ -502,8 +500,6 @@ typedef struct SettingsDataStruct { // #if ENABLED(DWIN_LCD_PROUI) uint8_t dwin_data[eeprom_data_size]; - #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - uint8_t dwin_settings[CrealityDWIN.eeprom_data_size]; #endif // @@ -541,7 +537,7 @@ typedef struct SettingsDataStruct { // Buzzer enable/disable // #if ENABLED(SOUND_MENU_ITEM) - bool buzzer_enabled; + bool sound_on; #endif // @@ -592,7 +588,7 @@ void MarlinSettings::postprocess() { xyze_pos_t oldpos = current_position; // steps per s2 needs to be updated to agree with units per s2 - planner.reset_acceleration_rates(); + planner.refresh_acceleration_rates(); // Make sure delta kinematics are updated before refreshing the // planner position so the stepper counts will be set correctly. @@ -615,7 +611,7 @@ void MarlinSettings::postprocess() { TERN_(ENABLE_LEVELING_FADE_HEIGHT, set_z_fade_height(new_z_fade_height, false)); // false = no report - TERN_(AUTO_BED_LEVELING_BILINEAR, bbl.refresh_bed_level()); + TERN_(AUTO_BED_LEVELING_BILINEAR, bedlevel.refresh_bed_level()); TERN_(HAS_MOTOR_CURRENT_PWM, stepper.refresh_motor_power()); @@ -844,7 +840,7 @@ void MarlinSettings::postprocess() { { #if ENABLED(MESH_BED_LEVELING) static_assert( - sizeof(mbl.z_values) == (GRID_MAX_POINTS) * sizeof(mbl.z_values[0][0]), + sizeof(bedlevel.z_values) == (GRID_MAX_POINTS) * sizeof(bedlevel.z_values[0][0]), "MBL Z array is the wrong size." ); #else @@ -854,12 +850,12 @@ void MarlinSettings::postprocess() { const uint8_t mesh_num_x = TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_X, 3), mesh_num_y = TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_Y, 3); - EEPROM_WRITE(TERN(MESH_BED_LEVELING, mbl.z_offset, dummyf)); + EEPROM_WRITE(TERN(MESH_BED_LEVELING, bedlevel.z_offset, dummyf)); EEPROM_WRITE(mesh_num_x); EEPROM_WRITE(mesh_num_y); #if ENABLED(MESH_BED_LEVELING) - EEPROM_WRITE(mbl.z_values); + EEPROM_WRITE(bedlevel.z_values); #else for (uint8_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_WRITE(dummyf); #endif @@ -896,7 +892,7 @@ void MarlinSettings::postprocess() { { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) static_assert( - sizeof(Z_VALUES_ARR) == (GRID_MAX_POINTS) * sizeof(Z_VALUES_ARR[0][0]), + sizeof(bedlevel.z_values) == (GRID_MAX_POINTS) * sizeof(bedlevel.z_values[0][0]), "Bilinear Z array is the wrong size." ); #endif @@ -906,16 +902,16 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(grid_max_x); EEPROM_WRITE(grid_max_y); #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - EEPROM_WRITE(bbl.get_grid_spacing()); - EEPROM_WRITE(bbl.get_grid_start()); + EEPROM_WRITE(bedlevel.grid_spacing); + EEPROM_WRITE(bedlevel.grid_start); #else - const xy_pos_t bilinear_start{0}, bilinear_grid_spacing{0}; + const xy_pos_t bilinear_grid_spacing{0}, bilinear_start{0}; EEPROM_WRITE(bilinear_grid_spacing); EEPROM_WRITE(bilinear_start); #endif #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - EEPROM_WRITE(Z_VALUES_ARR); // 9-256 floats + EEPROM_WRITE(bedlevel.z_values); // 9-256 floats #else dummyf = 0; for (uint16_t q = grid_max_x * grid_max_y; q--;) EEPROM_WRITE(dummyf); @@ -938,7 +934,7 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(planner_leveling_active); const bool ubl_active = TERN(AUTO_BED_LEVELING_UBL, planner.leveling_active, false); - const int8_t storage_slot = TERN(AUTO_BED_LEVELING_UBL, ubl.storage_slot, -1); + const int8_t storage_slot = TERN(AUTO_BED_LEVELING_UBL, bedlevel.storage_slot, -1); EEPROM_WRITE(ubl_active); EEPROM_WRITE(storage_slot); } @@ -1017,13 +1013,13 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(TERN(Y_DUAL_ENDSTOPS, endstops.y2_endstop_adj, dummyf)); // 1 float EEPROM_WRITE(TERN(Z_MULTI_ENDSTOPS, endstops.z2_endstop_adj, dummyf)); // 1 float - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPERS >= 3 EEPROM_WRITE(endstops.z3_endstop_adj); // 1 float #else EEPROM_WRITE(dummyf); #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPERS >= 4 EEPROM_WRITE(endstops.z4_endstop_adj); // 1 float #else EEPROM_WRITE(dummyf); @@ -1517,20 +1513,11 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(dwin_data); char dwin_data[eeprom_data_size] = { 0 }; - DWIN_StoreSettings(dwin_data); + DWIN_CopySettingsTo(dwin_data); EEPROM_WRITE(dwin_data); } #endif - #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) - { - _FIELD_TEST(dwin_settings); - char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; - CrealityDWIN.Save_Settings(dwin_settings); - EEPROM_WRITE(dwin_settings); - } - #endif - // // Case Light Brightness // @@ -1576,7 +1563,7 @@ void MarlinSettings::postprocess() { // Buzzer enable/disable // #if ENABLED(SOUND_MENU_ITEM) - EEPROM_WRITE(ui.buzzer_enabled); + EEPROM_WRITE(ui.sound_on); #endif // @@ -1638,8 +1625,8 @@ void MarlinSettings::postprocess() { // UBL Mesh // #if ENABLED(UBL_SAVE_ACTIVE_ON_M500) - if (ubl.storage_slot >= 0) - store_mesh(ubl.storage_slot); + if (bedlevel.storage_slot >= 0) + store_mesh(bedlevel.storage_slot); #endif if (!eeprom_error) { @@ -1796,20 +1783,20 @@ void MarlinSettings::postprocess() { EEPROM_READ_ALWAYS(mesh_num_y); #if ENABLED(MESH_BED_LEVELING) - if (!validating) mbl.z_offset = dummyf; + if (!validating) bedlevel.z_offset = dummyf; 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); + EEPROM_READ(bedlevel.z_values); } else { // EEPROM data is stale - if (!validating) mbl.reset(); + if (!validating) bedlevel.reset(); for (uint16_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_READ(dummyf); } #else // MBL is disabled - skip the stored data for (uint16_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_READ(dummyf); - #endif // MESH_BED_LEVELING + #endif } // @@ -1849,8 +1836,8 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) if (grid_max_x == (GRID_MAX_POINTS_X) && grid_max_y == (GRID_MAX_POINTS_Y)) { if (!validating) set_bed_leveling_enabled(false); - bbl.set_grid(spacing, start); - EEPROM_READ(Z_VALUES_ARR); // 9 to 256 floats + bedlevel.set_grid(spacing, start); + EEPROM_READ(bedlevel.z_values); // 9 to 256 floats } else // EEPROM data is stale #endif // AUTO_BED_LEVELING_BILINEAR @@ -1877,7 +1864,7 @@ void MarlinSettings::postprocess() { _FIELD_TEST(planner_leveling_active); #if ENABLED(AUTO_BED_LEVELING_UBL) const bool &planner_leveling_active = planner.leveling_active; - const int8_t &ubl_storage_slot = ubl.storage_slot; + const int8_t &ubl_storage_slot = bedlevel.storage_slot; #else bool planner_leveling_active; int8_t ubl_storage_slot; @@ -1969,12 +1956,12 @@ void MarlinSettings::postprocess() { EEPROM_READ(TERN(Y_DUAL_ENDSTOPS, endstops.y2_endstop_adj, dummyf)); // 1 float EEPROM_READ(TERN(Z_MULTI_ENDSTOPS, endstops.z2_endstop_adj, dummyf)); // 1 float - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPERS >= 3 EEPROM_READ(endstops.z3_endstop_adj); // 1 float #else EEPROM_READ(dummyf); #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPERS >= 4 EEPROM_READ(endstops.z4_endstop_adj); // 1 float #else EEPROM_READ(dummyf); @@ -2493,14 +2480,7 @@ void MarlinSettings::postprocess() { const char dwin_data[eeprom_data_size] = { 0 }; _FIELD_TEST(dwin_data); EEPROM_READ(dwin_data); - if (!validating) DWIN_LoadSettings(dwin_data); - } - #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - { - const char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; - _FIELD_TEST(dwin_settings); - EEPROM_READ(dwin_settings); - if (!validating) CrealityDWIN.Load_Settings(dwin_settings); + if (!validating) DWIN_CopySettingsFrom(dwin_data); } #endif @@ -2546,8 +2526,8 @@ void MarlinSettings::postprocess() { // Buzzer enable/disable // #if ENABLED(SOUND_MENU_ITEM) - _FIELD_TEST(buzzer_enabled); - EEPROM_READ(ui.buzzer_enabled); + _FIELD_TEST(sound_on); + EEPROM_READ(ui.sound_on); #endif // @@ -2617,11 +2597,11 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) if (!validating) { - ubl.report_state(); + bedlevel.report_state(); - if (!ubl.sanity_check()) { + if (!bedlevel.sanity_check()) { #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) - ubl.echo_name(); + bedlevel.echo_name(); DEBUG_ECHOLNPGM(" initialized.\n"); #endif } @@ -2629,18 +2609,18 @@ void MarlinSettings::postprocess() { eeprom_error = true; #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) DEBUG_ECHOPGM("?Can't enable "); - ubl.echo_name(); + bedlevel.echo_name(); DEBUG_ECHOLNPGM("."); #endif - ubl.reset(); + bedlevel.reset(); } - if (ubl.storage_slot >= 0) { - load_mesh(ubl.storage_slot); - DEBUG_ECHOLNPGM("Mesh ", ubl.storage_slot, " loaded from storage."); + if (bedlevel.storage_slot >= 0) { + load_mesh(bedlevel.storage_slot); + DEBUG_ECHOLNPGM("Mesh ", bedlevel.storage_slot, " loaded from storage."); } else { - ubl.reset(); + bedlevel.reset(); DEBUG_ECHOLNPGM("UBL reset"); } } @@ -2708,7 +2688,7 @@ void MarlinSettings::postprocess() { return (datasize() + EEPROM_OFFSET + 32) & 0xFFF8; } - #define MESH_STORE_SIZE sizeof(TERN(OPTIMIZED_MESH_STORAGE, mesh_store_t, ubl.z_values)) + #define MESH_STORE_SIZE sizeof(TERN(OPTIMIZED_MESH_STORAGE, mesh_store_t, bedlevel.z_values)) uint16_t MarlinSettings::calc_num_meshes() { return (meshes_end - meshes_start_index()) / MESH_STORE_SIZE; @@ -2734,10 +2714,10 @@ void MarlinSettings::postprocess() { #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); + bedlevel.set_store_from_mesh(bedlevel.z_values, z_mesh_store); uint8_t * const src = (uint8_t*)&z_mesh_store; #else - uint8_t * const src = (uint8_t*)&ubl.z_values; + uint8_t * const src = (uint8_t*)&bedlevel.z_values; #endif // Write crc to MAT along with other data, or just tack on to the beginning or end @@ -2772,7 +2752,7 @@ void MarlinSettings::postprocess() { 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; + uint8_t * const dest = into ? (uint8_t*)into : (uint8_t*)&bedlevel.z_values; #endif persistentStore.access_start(); @@ -2782,11 +2762,11 @@ void MarlinSettings::postprocess() { #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); + bedlevel.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); + bedlevel.set_mesh_from_store(z_mesh_store, bedlevel.z_values); #endif if (status) SERIAL_ECHOLNPGM("?Unable to load mesh data."); @@ -2929,9 +2909,6 @@ void MarlinSettings::reset() { #endif #endif - TERN_(DWIN_LCD_PROUI, DWIN_SetDataDefaults()); - TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Reset_Settings()); - // // Case Light Brightness // @@ -2945,7 +2922,9 @@ void MarlinSettings::reset() { // // Buzzer enable/disable // - TERN_(SOUND_MENU_ITEM, ui.buzzer_enabled = true); + #if ENABLED(SOUND_MENU_ITEM) + ui.sound_on = ENABLED(SOUND_ON_DEFAULT); + #endif // // Magnetic Parking Extruder @@ -3042,13 +3021,13 @@ void MarlinSettings::reset() { #define Z2_ENDSTOP_ADJUSTMENT 0 #endif endstops.z2_endstop_adj = Z2_ENDSTOP_ADJUSTMENT; - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 #ifndef Z3_ENDSTOP_ADJUSTMENT #define Z3_ENDSTOP_ADJUSTMENT 0 #endif endstops.z3_endstop_adj = Z3_ENDSTOP_ADJUSTMENT; #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 #ifndef Z4_ENDSTOP_ADJUSTMENT #define Z4_ENDSTOP_ADJUSTMENT 0 #endif @@ -3302,6 +3281,11 @@ void MarlinSettings::reset() { // TERN_(DGUS_LCD_UI_MKS, MKS_reset_settings()); + // + // Ender-3 V2 with ProUI + // + TERN_(DWIN_LCD_PROUI, DWIN_SetDataDefaults()); + // // Model predictive control // @@ -3313,6 +3297,7 @@ void MarlinSettings::reset() { #if ENABLED(MPC_INCLUDE_FAN) constexpr float _mpc_ambient_xfer_coeff_fan255[] = MPC_AMBIENT_XFER_COEFF_FAN255; #endif + constexpr float _filament_heat_capacity_permm[] = FILAMENT_HEAT_CAPACITY_PERMM; static_assert(COUNT(_mpc_heater_power) == HOTENDS, "MPC_HEATER_POWER must have HOTENDS items."); static_assert(COUNT(_mpc_block_heat_capacity) == HOTENDS, "MPC_BLOCK_HEAT_CAPACITY must have HOTENDS items."); @@ -3321,6 +3306,7 @@ void MarlinSettings::reset() { #if ENABLED(MPC_INCLUDE_FAN) static_assert(COUNT(_mpc_ambient_xfer_coeff_fan255) == HOTENDS, "MPC_AMBIENT_XFER_COEFF_FAN255 must have HOTENDS items."); #endif + static_assert(COUNT(_filament_heat_capacity_permm) == HOTENDS, "FILAMENT_HEAT_CAPACITY_PERMM must have HOTENDS items."); HOTEND_LOOP() { thermalManager.temp_hotend[e].constants.heater_power = _mpc_heater_power[e]; @@ -3330,6 +3316,7 @@ void MarlinSettings::reset() { #if ENABLED(MPC_INCLUDE_FAN) thermalManager.temp_hotend[e].constants.fan255_adjustment = _mpc_ambient_xfer_coeff_fan255[e] - _mpc_ambient_xfer_coeff[e]; #endif + thermalManager.temp_hotend[e].constants.filament_heat_capacity_permm = _filament_heat_capacity_permm[e]; } #endif @@ -3435,24 +3422,25 @@ void MarlinSettings::reset() { LOOP_L_N(px, GRID_MAX_POINTS_X) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" G29 S3 I", px, " J", py); - SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(mbl.z_values[px][py]), 5); + SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(bedlevel.z_values[px][py]), 5); } } CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_F(" G29 S4 Z", LINEAR_UNIT(mbl.z_offset), 5); + SERIAL_ECHOLNPAIR_F(" G29 S4 Z", LINEAR_UNIT(bedlevel.z_offset), 5); } #elif ENABLED(AUTO_BED_LEVELING_UBL) if (!forReplay) { SERIAL_EOL(); - ubl.report_state(); - SERIAL_ECHO_MSG("Active Mesh Slot ", ubl.storage_slot); + bedlevel.report_state(); + SERIAL_ECHO_MSG("Active Mesh Slot ", bedlevel.storage_slot); SERIAL_ECHO_MSG("EEPROM can hold ", calc_num_meshes(), " meshes.\n"); } - //ubl.report_current_mesh(); // This is too verbose for large meshes. A better (more terse) - // solution needs to be found. + //bedlevel.report_current_mesh(); // This is too verbose for large meshes. A better (more terse) + // solution needs to be found. + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) if (leveling_is_valid()) { @@ -3460,7 +3448,7 @@ void MarlinSettings::reset() { LOOP_L_N(px, GRID_MAX_POINTS_X) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" G29 W I", px, " J", py); - SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(Z_VALUES_ARR[px][py]), 5); + SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(bedlevel.z_values[px][py]), 5); } } } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 1140a6eb1e38..4832220abd75 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -84,7 +84,7 @@ Stepper stepper; // Singleton #define BABYSTEPPING_EXTRA_DIR_WAIT #ifdef __AVR__ - #include "speed_lookuptable.h" + #include "stepper/speed_lookuptable.h" #endif #include "endstops.h" @@ -177,9 +177,9 @@ bool Stepper::abort_current_block; #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 , Stepper::locked_Z3_motor = false - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 , Stepper::locked_Z4_motor = false #endif #endif @@ -253,20 +253,6 @@ xyz_long_t Stepper::endstops_trigsteps; xyze_long_t Stepper::count_position{0}; xyze_int8_t Stepper::count_direction{0}; -#if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - Stepper::stepper_laser_t Stepper::laser_trap = { - .enabled = false, - .cur_power = 0, - .cruise_set = false, - #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) - .last_step_count = 0, - .acc_step_count = 0 - #else - .till_update = 0 - #endif - }; -#endif - #define MINDIR(A) (count_direction[_AXIS(A)] < 0) #define MAXDIR(A) (count_direction[_AXIS(A)] > 0) @@ -365,7 +351,7 @@ xyze_int8_t Stepper::count_direction{0}; A##4_STEP_WRITE(V); \ } -#if ENABLED(X_DUAL_STEPPER_DRIVERS) +#if HAS_DUAL_X_STEPPERS #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) @@ -386,7 +372,7 @@ xyze_int8_t Stepper::count_direction{0}; #define X_APPLY_STEP(v,Q) X_STEP_WRITE(v) #endif -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) +#if HAS_DUAL_Y_STEPPERS #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) @@ -398,7 +384,7 @@ xyze_int8_t Stepper::count_direction{0}; #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v) #endif -#if NUM_Z_STEPPER_DRIVERS == 4 +#if NUM_Z_STEPPERS == 4 #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)); \ @@ -410,7 +396,7 @@ xyze_int8_t Stepper::count_direction{0}; #else #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 +#elif NUM_Z_STEPPERS == 3 #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) @@ -421,7 +407,7 @@ xyze_int8_t Stepper::count_direction{0}; #else #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 +#elif NUM_Z_STEPPERS == 2 #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) @@ -498,11 +484,7 @@ xyze_int8_t Stepper::count_direction{0}; void Stepper::enable_axis(const AxisEnum axis) { #define _CASE_ENABLE(N) case N##_AXIS: ENABLE_AXIS_##N(); break; switch (axis) { - NUM_AXIS_CODE( - _CASE_ENABLE(X), _CASE_ENABLE(Y), _CASE_ENABLE(Z), - _CASE_ENABLE(I), _CASE_ENABLE(J), _CASE_ENABLE(K), - _CASE_ENABLE(U), _CASE_ENABLE(V), _CASE_ENABLE(W) - ); + MAIN_AXIS_MAP(_CASE_ENABLE) default: break; } mark_axis_enabled(axis); @@ -518,11 +500,7 @@ bool Stepper::disable_axis(const AxisEnum axis) { if (can_disable) { #define _CASE_DISABLE(N) case N##_AXIS: DISABLE_AXIS_##N(); break; switch (axis) { - NUM_AXIS_CODE( - _CASE_DISABLE(X), _CASE_DISABLE(Y), _CASE_DISABLE(Z), - _CASE_DISABLE(I), _CASE_DISABLE(J), _CASE_DISABLE(K), - _CASE_DISABLE(U), _CASE_DISABLE(V), _CASE_DISABLE(W) - ); + MAIN_AXIS_MAP(_CASE_DISABLE) default: break; } } @@ -619,7 +597,7 @@ void Stepper::set_directions() { #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) // Because this is valid for the whole block we don't know - // what e-steppers will step. Likely all. Set all. + // what E steppers will step. Likely all. Set all. if (motor_direction(E_AXIS)) { MIXER_STEPPER_LOOP(j) REV_E_DIR(j); count_direction.e = -1; @@ -1707,7 +1685,7 @@ void Stepper::pulse_phase_isr() { }while(0) // Direct Stepping page? - const bool is_page = IS_PAGE(current_block); + const bool is_page = current_block->is_page(); #if ENABLED(DIRECT_STEPPING) // Direct stepping is currently not ready for HAS_I_AXIS @@ -1906,9 +1884,7 @@ void Stepper::pulse_phase_isr() { #endif #endif - #if ENABLED(I2S_STEPPER_STREAM) - i2s_push_sample(); - #endif + TERN_(I2S_STEPPER_STREAM, i2s_push_sample()); // TODO: need to deal with MINIMUM_STEPPER_PULSE over i2s #if ISR_MULTI_STEPS @@ -1974,7 +1950,6 @@ uint32_t Stepper::block_phase_isr() { // If there is a current block if (current_block) { - // If current block is finished, reset pointer and finalize state if (step_events_completed >= step_event_count) { #if ENABLED(DIRECT_STEPPING) @@ -1987,7 +1962,7 @@ uint32_t Stepper::block_phase_isr() { count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] * count_direction[_AXIS(AXIS)]; #endif - if (IS_PAGE(current_block)) { + if (current_block->is_page()) { PAGE_SEGMENT_UPDATE_POS(X); PAGE_SEGMENT_UPDATE_POS(Y); PAGE_SEGMENT_UPDATE_POS(Z); @@ -2027,32 +2002,28 @@ uint32_t Stepper::block_phase_isr() { else if (LA_steps) nextAdvanceISR = 0; #endif - // Update laser - Accelerating - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - if (laser_trap.enabled) { - #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) - if (current_block->laser.entry_per) { - laser_trap.acc_step_count -= step_events_completed - laser_trap.last_step_count; - laser_trap.last_step_count = step_events_completed; - - // Should be faster than a divide, since this should trip just once - if (laser_trap.acc_step_count < 0) { - while (laser_trap.acc_step_count < 0) { - laser_trap.acc_step_count += current_block->laser.entry_per; - if (laser_trap.cur_power < current_block->laser.power) laser_trap.cur_power++; - } - cutter.ocr_set_power(laser_trap.cur_power); - } - } - #else - if (laser_trap.till_update) - laser_trap.till_update--; - else { - laser_trap.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; - laser_trap.cur_power = (current_block->laser.power * acc_step_rate) / current_block->nominal_rate; - cutter.ocr_set_power(laser_trap.cur_power); // Cycle efficiency is irrelevant it the last line was many cycles + /* + * Adjust Laser Power - Accelerating + * isPowered - True when a move is powered. + * isEnabled - laser power is active. + * Laser power variables are calulated and stored in this block by the planner code. + * + * trap_ramp_active_pwr - the active power in this block across accel or decel trap steps. + * trap_ramp_entry_incr - holds the precalculated value to increase the current power per accel step. + * + * Apply the starting active power and then increase power per step by the trap_ramp_entry_incr value if positive. + */ + + #if ENABLED(LASER_POWER_TRAP) + if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS) { + if (planner.laser_inline.status.isPowered && planner.laser_inline.status.isEnabled) { + if (current_block->laser.trap_ramp_entry_incr > 0) { + cutter.apply_power(current_block->laser.trap_ramp_active_pwr); + current_block->laser.trap_ramp_active_pwr += current_block->laser.trap_ramp_entry_incr; } - #endif + } + // Not a powered move. + else cutter.apply_power(0); } #endif } @@ -2076,7 +2047,6 @@ uint32_t Stepper::block_phase_isr() { : current_block->final_rate; } #else - // Using the old trapezoidal control step_rate = STEP_MULTIPLY(deceleration_time, current_block->acceleration_rate); if (step_rate < acc_step_rate) { // Still decelerating? @@ -2104,37 +2074,25 @@ uint32_t Stepper::block_phase_isr() { else if (LA_steps) nextAdvanceISR = 0; #endif // LIN_ADVANCE - // Update laser - Decelerating - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - if (laser_trap.enabled) { - #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) - if (current_block->laser.exit_per) { - laser_trap.acc_step_count -= step_events_completed - laser_trap.last_step_count; - laser_trap.last_step_count = step_events_completed; - - // Should be faster than a divide, since this should trip just once - if (laser_trap.acc_step_count < 0) { - while (laser_trap.acc_step_count < 0) { - laser_trap.acc_step_count += current_block->laser.exit_per; - if (laser_trap.cur_power > current_block->laser.power_exit) laser_trap.cur_power--; - } - cutter.ocr_set_power(laser_trap.cur_power); - } - } - #else - if (laser_trap.till_update) - laser_trap.till_update--; - else { - laser_trap.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; - laser_trap.cur_power = (current_block->laser.power * step_rate) / current_block->nominal_rate; - cutter.ocr_set_power(laser_trap.cur_power); // Cycle efficiency isn't relevant when the last line was many cycles + /* + * Adjust Laser Power - Decelerating + * trap_ramp_entry_decr - holds the precalculated value to decrease the current power per decel step. + */ + #if ENABLED(LASER_POWER_TRAP) + if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS) { + if (planner.laser_inline.status.isPowered && planner.laser_inline.status.isEnabled) { + if (current_block->laser.trap_ramp_exit_decr > 0) { + current_block->laser.trap_ramp_active_pwr -= current_block->laser.trap_ramp_exit_decr; + cutter.apply_power(current_block->laser.trap_ramp_active_pwr); } - #endif + // Not a powered move. + else cutter.apply_power(0); + } } #endif + } - // Must be in cruise phase otherwise - else { + else { // Must be in cruise phase otherwise #if ENABLED(LIN_ADVANCE) // If there are any esteps, fire the next advance_isr "now" @@ -2149,24 +2107,50 @@ uint32_t Stepper::block_phase_isr() { // The timer interval is just the nominal value for the nominal speed interval = ticks_nominal; + } - // Update laser - Cruising - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - if (laser_trap.enabled) { - if (!laser_trap.cruise_set) { - laser_trap.cur_power = current_block->laser.power; - cutter.ocr_set_power(laser_trap.cur_power); - laser_trap.cruise_set = true; + /* Adjust Laser Power - Cruise + * power - direct or floor adjusted active laser power. + */ + + #if ENABLED(LASER_POWER_TRAP) + if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS) { + if (step_events_completed + 1 == accelerate_until) { + if (planner.laser_inline.status.isPowered && planner.laser_inline.status.isEnabled) { + if (current_block->laser.trap_ramp_entry_incr > 0) { + current_block->laser.trap_ramp_active_pwr = current_block->laser.power; + cutter.apply_power(current_block->laser.power); + } } - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) - laser_trap.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; - #else - laser_trap.last_step_count = step_events_completed; - #endif + // Not a powered move. + else cutter.apply_power(0); } - #endif - } + } + #endif } + + #if ENABLED(LASER_FEATURE) + /* + * CUTTER_MODE_DYNAMIC is experimental and developing. + * Super-fast method to dynamically adjust the laser power OCR value based on the input feedrate in mm-per-minute. + * TODO: Set up Min/Max OCR offsets to allow tuning and scaling of various lasers. + * TODO: Integrate accel/decel +-rate into the dynamic laser power calc. + */ + if (cutter.cutter_mode == CUTTER_MODE_DYNAMIC + && planner.laser_inline.status.isPowered // isPowered flag set on any parsed G1, G2, G3, or G5 move; cleared on any others. + && cutter.last_block_power != current_block->laser.power // Prevent constant update without change + ) { + cutter.apply_power(current_block->laser.power); + cutter.last_block_power = current_block->laser.power; + } + #endif + } + else { // !current_block + #if ENABLED(LASER_FEATURE) + if (cutter.cutter_mode == CUTTER_MODE_DYNAMIC) { + cutter.apply_power(0); // No movement in dynamic mode so turn Laser off + } + #endif } // If there is no current block at this point, attempt to pop one from the buffer @@ -2177,16 +2161,20 @@ uint32_t Stepper::block_phase_isr() { if ((current_block = planner.get_current_block())) { // Sync block? Sync the stepper counts or fan speeds and return - while (current_block->flag & BLOCK_MASK_SYNC) { + while (current_block->is_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; + #if ENABLED(LASER_POWER_SYNC) + if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS) { + if (current_block->is_pwr_sync()) { + planner.laser_inline.status.isSyncPower = true; + cutter.apply_power(current_block->laser.power); + } + } #endif - if (!is_sync_fans) _set_position(current_block->position); + TERN_(LASER_SYNCHRONOUS_M106_M107, if (current_block->is_fan_sync()) planner.sync_fan_speeds(current_block->fan_speed)); + + if (!(current_block->is_fan_sync() || current_block->is_pwr_sync())) _set_position(current_block->position); discard_current_block(); @@ -2196,8 +2184,10 @@ uint32_t Stepper::block_phase_isr() { } // For non-inline cutter, grossly apply power - #if ENABLED(LASER_FEATURE) && DISABLED(LASER_POWER_INLINE) - cutter.apply_power(current_block->cutter_power); + #if HAS_CUTTER + if (cutter.cutter_mode == CUTTER_MODE_STANDARD) { + cutter.apply_power(current_block->cutter_power); + } #endif #if ENABLED(POWER_LOSS_RECOVERY) @@ -2206,7 +2196,7 @@ uint32_t Stepper::block_phase_isr() { #endif #if ENABLED(DIRECT_STEPPING) - if (IS_PAGE(current_block)) { + if (current_block->is_page()) { page_step_state.segment_steps = 0; page_step_state.segment_idx = 0; page_step_state.page = page_manager.get_page(current_block->page_idx); @@ -2370,36 +2360,22 @@ uint32_t Stepper::block_phase_isr() { set_directions(current_block->direction_bits); } - #if ENABLED(LASER_POWER_INLINE) - const power_status_t stat = current_block->laser.status; - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - laser_trap.enabled = stat.isPlanned && stat.isEnabled; - laser_trap.cur_power = current_block->laser.power_entry; // RESET STATE - laser_trap.cruise_set = false; - #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) - laser_trap.last_step_count = 0; - laser_trap.acc_step_count = current_block->laser.entry_per / 2; - #else - laser_trap.till_update = 0; - #endif - // Always have PWM in this case - if (stat.isPlanned) { // Planner controls the laser - cutter.ocr_set_power( - stat.isEnabled ? laser_trap.cur_power : 0 // ON with power or OFF - ); - } - #else - if (stat.isPlanned) { // Planner controls the laser - #if ENABLED(SPINDLE_LASER_USE_PWM) - cutter.ocr_set_power( - stat.isEnabled ? current_block->laser.power : 0 // ON with power or OFF - ); + #if ENABLED(LASER_FEATURE) + if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS) { // Planner controls the laser + if (planner.laser_inline.status.isSyncPower) + // If the previous block was a M3 sync power then skip the trap power init otherwise it will 0 the sync power. + planner.laser_inline.status.isSyncPower = false; // Clear the flag to process subsequent trap calc's. + else if (current_block->laser.status.isEnabled) { + #if ENABLED(LASER_POWER_TRAP) + TERN_(DEBUG_LASER_TRAP, SERIAL_ECHO_MSG("InitTrapPwr:",current_block->laser.trap_ramp_active_pwr)); + cutter.apply_power(current_block->laser.status.isPowered ? current_block->laser.trap_ramp_active_pwr : 0); #else - cutter.set_enabled(stat.isEnabled); + TERN_(DEBUG_CUTTER_POWER, SERIAL_ECHO_MSG("InlinePwr:",current_block->laser.power)); + cutter.apply_power(current_block->laser.status.isPowered ? current_block->laser.power : 0); #endif } - #endif - #endif // LASER_POWER_INLINE + } + #endif // LASER_FEATURE // If the endstop is already pressed, endstop interrupts won't invoke // endstop_triggered and the move will grind. So check here for a @@ -2429,21 +2405,6 @@ uint32_t Stepper::block_phase_isr() { // Calculate the initial timer interval interval = calc_timer_interval(current_block->initial_rate, &steps_per_isr); } - #if ENABLED(LASER_POWER_INLINE_CONTINUOUS) - else { // No new block found; so apply inline laser parameters - // This should mean ending file with 'M5 I' will stop the laser; thus the inline flag isn't needed - const power_status_t stat = planner.laser_inline.status; - if (stat.isPlanned) { // Planner controls the laser - #if ENABLED(SPINDLE_LASER_USE_PWM) - cutter.ocr_set_power( - stat.isEnabled ? planner.laser_inline.power : 0 // ON with power or OFF - ); - #else - cutter.set_enabled(stat.isEnabled); - #endif - } - } - #endif } // Return the interval to wait @@ -2613,19 +2574,19 @@ void Stepper::init() { TERN_(HAS_X2_DIR, X2_DIR_INIT()); #if HAS_Y_DIR Y_DIR_INIT(); - #if BOTH(Y_DUAL_STEPPER_DRIVERS, HAS_Y2_DIR) + #if BOTH(HAS_DUAL_Y_STEPPERS, HAS_Y2_DIR) Y2_DIR_INIT(); #endif #endif #if HAS_Z_DIR Z_DIR_INIT(); - #if NUM_Z_STEPPER_DRIVERS >= 2 && HAS_Z2_DIR + #if NUM_Z_STEPPERS >= 2 && HAS_Z2_DIR Z2_DIR_INIT(); #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 && HAS_Z3_DIR + #if NUM_Z_STEPPERS >= 3 && HAS_Z3_DIR Z3_DIR_INIT(); #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 && HAS_Z4_DIR + #if NUM_Z_STEPPERS >= 4 && HAS_Z4_DIR Z4_DIR_INIT(); #endif #endif @@ -2684,7 +2645,7 @@ void Stepper::init() { #if HAS_Y_ENABLE Y_ENABLE_INIT(); if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH); - #if BOTH(Y_DUAL_STEPPER_DRIVERS, HAS_Y2_ENABLE) + #if BOTH(HAS_DUAL_Y_STEPPERS, HAS_Y2_ENABLE) Y2_ENABLE_INIT(); if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH); #endif @@ -2692,15 +2653,15 @@ void Stepper::init() { #if HAS_Z_ENABLE Z_ENABLE_INIT(); if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH); - #if NUM_Z_STEPPER_DRIVERS >= 2 && HAS_Z2_ENABLE + #if NUM_Z_STEPPERS >= 2 && HAS_Z2_ENABLE Z2_ENABLE_INIT(); if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH); #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 && HAS_Z3_ENABLE + #if NUM_Z_STEPPERS >= 3 && HAS_Z3_ENABLE Z3_ENABLE_INIT(); if (!Z_ENABLE_ON) Z3_ENABLE_WRITE(HIGH); #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 && HAS_Z4_ENABLE + #if NUM_Z_STEPPERS >= 4 && HAS_Z4_ENABLE Z4_ENABLE_INIT(); if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH); #endif @@ -2775,7 +2736,7 @@ void Stepper::init() { // Init Step Pins #if HAS_X_STEP - #if EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) + #if HAS_X2_STEPPER X2_STEP_INIT(); X2_STEP_WRITE(INVERT_X_STEP_PIN); #endif @@ -2783,7 +2744,7 @@ void Stepper::init() { #endif #if HAS_Y_STEP - #if ENABLED(Y_DUAL_STEPPER_DRIVERS) + #if HAS_DUAL_Y_STEPPERS Y2_STEP_INIT(); Y2_STEP_WRITE(INVERT_Y_STEP_PIN); #endif @@ -2791,15 +2752,15 @@ void Stepper::init() { #endif #if HAS_Z_STEP - #if NUM_Z_STEPPER_DRIVERS >= 2 + #if NUM_Z_STEPPERS >= 2 Z2_STEP_INIT(); Z2_STEP_WRITE(INVERT_Z_STEP_PIN); #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 Z3_STEP_INIT(); Z3_STEP_WRITE(INVERT_Z_STEP_PIN); #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 Z4_STEP_INIT(); Z4_STEP_WRITE(INVERT_Z_STEP_PIN); #endif @@ -3058,7 +3019,7 @@ void Stepper::report_positions() { #define _ENABLE_AXIS(A) enable_axis(_AXIS(A)) #define _READ_DIR(AXIS) AXIS ##_DIR_READ() - #define _INVERT_DIR(AXIS) INVERT_## AXIS ##_DIR + #define _INVERT_DIR(AXIS) ENABLED(INVERT_## AXIS ##_DIR) #define _APPLY_DIR(AXIS, INVERT) AXIS ##_APPLY_DIR(INVERT, true) #if MINIMUM_STEPPER_PULSE @@ -3203,30 +3164,30 @@ void Stepper::report_positions() { U_DIR_READ(), V_DIR_READ(), W_DIR_READ() ); - X_DIR_WRITE(INVERT_X_DIR ^ z_direction); + X_DIR_WRITE(ENABLED(INVERT_X_DIR) ^ z_direction); #ifdef Y_DIR_WRITE - Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction); + Y_DIR_WRITE(ENABLED(INVERT_Y_DIR) ^ z_direction); #endif #ifdef Z_DIR_WRITE - Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction); + Z_DIR_WRITE(ENABLED(INVERT_Z_DIR) ^ z_direction); #endif #ifdef I_DIR_WRITE - I_DIR_WRITE(INVERT_I_DIR ^ z_direction); + I_DIR_WRITE(ENABLED(INVERT_I_DIR) ^ z_direction); #endif #ifdef J_DIR_WRITE - J_DIR_WRITE(INVERT_J_DIR ^ z_direction); + J_DIR_WRITE(ENABLED(INVERT_J_DIR) ^ z_direction); #endif #ifdef K_DIR_WRITE - K_DIR_WRITE(INVERT_K_DIR ^ z_direction); + K_DIR_WRITE(ENABLED(INVERT_K_DIR) ^ z_direction); #endif #ifdef U_DIR_WRITE - U_DIR_WRITE(INVERT_U_DIR ^ z_direction); + U_DIR_WRITE(ENABLED(INVERT_U_DIR) ^ z_direction); #endif #ifdef V_DIR_WRITE - V_DIR_WRITE(INVERT_V_DIR ^ z_direction); + V_DIR_WRITE(ENABLED(INVERT_V_DIR) ^ z_direction); #endif #ifdef W_DIR_WRITE - W_DIR_WRITE(INVERT_W_DIR ^ z_direction); + W_DIR_WRITE(ENABLED(INVERT_W_DIR) ^ z_direction); #endif DIR_WAIT_AFTER(); diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index fbbef2bb9c8b..787599ce3115 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -46,7 +46,7 @@ #include "planner.h" #include "stepper/indirection.h" #ifdef __AVR__ - #include "speed_lookuptable.h" + #include "stepper/speed_lookuptable.h" #endif // Disable multiple steps per ISR @@ -214,7 +214,7 @@ // Directions are set up for MIXING_STEPPERS - like before. // Finding the right stepper may last up to MIXING_STEPPERS loops in get_next_stepper(). // These loops are a bit faster than advancing a bresenham counter. - // Always only one e-stepper is stepped. + // Always only one E stepper is stepped. #define MIN_ISR_LA_LOOP_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES)) #else #define MIN_ISR_LA_LOOP_CYCLES ISR_STEPPER_CYCLES @@ -246,7 +246,11 @@ #define MIN_STEP_ISR_FREQUENCY (MAX_STEP_ISR_FREQUENCY_1X / 2) #define ENABLE_COUNT (NUM_AXES + E_STEPPERS) -typedef IF<(ENABLE_COUNT > 8), uint16_t, uint8_t>::type ena_mask_t; +#if ENABLE_COUNT > 16 + typedef uint32_t ena_mask_t; +#else + typedef IF<(ENABLE_COUNT > 8), uint16_t, uint8_t>::type ena_mask_t; +#endif // Axis flags type, for enabled state or other simple state typedef struct { @@ -259,8 +263,6 @@ typedef struct { #endif }; }; - constexpr ena_mask_t linear_bits() { return _BV(NUM_AXES) - 1; } - constexpr ena_mask_t e_bits() { return (_BV(EXTRUDERS) - 1) << NUM_AXES; } } stepper_flags_t; // All the stepper enable pins @@ -366,9 +368,9 @@ class Stepper { #endif #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) static bool locked_Z_motor, locked_Z2_motor - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 , locked_Z3_motor - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 , locked_Z4_motor #endif #endif @@ -442,25 +444,6 @@ class Stepper { // Current stepper motor directions (+1 or -1) static xyze_int8_t count_direction; - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - - typedef struct { - bool enabled; // Trapezoid needed flag (i.e., laser on, planner in control) - uint8_t cur_power; // Current laser power - bool cruise_set; // Power set up for cruising? - - #if ENABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) - uint16_t till_update; // Countdown to the next update - #else - uint32_t last_step_count, // Step count from the last update - acc_step_count; // Bresenham counter for laser accel/decel - #endif - } stepper_laser_t; - - static stepper_laser_t laser_trap; - - #endif - public: // Initialize stepper hardware static void init(); @@ -522,8 +505,7 @@ class Stepper { // Discard current block and free any resources FORCE_INLINE static void discard_current_block() { #if ENABLED(DIRECT_STEPPING) - if (IS_PAGE(current_block)) - page_manager.free_page(current_block->page_idx); + if (current_block->is_page()) page_manager.free_page(current_block->page_idx); #endif current_block = nullptr; axis_did_move = 0; @@ -570,18 +552,18 @@ class Stepper { #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) FORCE_INLINE static void set_z1_lock(const bool state) { locked_Z_motor = state; } FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; } - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; } - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 FORCE_INLINE static void set_z4_lock(const bool state) { locked_Z4_motor = state; } #endif #endif static void set_all_z_lock(const bool lock, const int8_t except=-1) { set_z1_lock(lock ^ (except == 0)); set_z2_lock(lock ^ (except == 1)); - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if NUM_Z_STEPPERS >= 3 set_z3_lock(lock ^ (except == 2)); - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if NUM_Z_STEPPERS >= 4 set_z4_lock(lock ^ (except == 3)); #endif #endif diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 879185ca14ef..687a0f289628 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -462,91 +462,91 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #if EXTRUDERS > 7 #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else if (E < 6) { E2_STEP_WRITE(V); } else { E3_STEP_WRITE(V); } }while(0) #define NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 4: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 5: E2_DIR_WRITE( INVERT_E2_DIR); break; \ - case 6: E3_DIR_WRITE( INVERT_E3_DIR); break; case 7: E3_DIR_WRITE( INVERT_E3_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 4: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; case 5: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; \ + case 6: E3_DIR_WRITE( ENABLED(INVERT_E3_DIR)); break; case 7: E3_DIR_WRITE( ENABLED(INVERT_E3_DIR)); break; \ } }while(0) #define REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 4: E2_DIR_WRITE( INVERT_E2_DIR); break; case 5: E2_DIR_WRITE(!INVERT_E2_DIR); break; \ - case 6: E3_DIR_WRITE(!INVERT_E3_DIR); break; case 7: E3_DIR_WRITE(!INVERT_E3_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 4: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; case 5: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; \ + case 6: E3_DIR_WRITE(DISABLED(INVERT_E3_DIR)); break; case 7: E3_DIR_WRITE(DISABLED(INVERT_E3_DIR)); break; \ } }while(0) #elif EXTRUDERS > 6 #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else if (E < 6) { E2_STEP_WRITE(V); } else { E3_STEP_WRITE(V); } }while(0) #define NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 4: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 5: E2_DIR_WRITE( INVERT_E2_DIR); break; \ - case 6: E3_DIR_WRITE( INVERT_E3_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 4: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; case 5: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; \ + case 6: E3_DIR_WRITE( ENABLED(INVERT_E3_DIR)); break; \ } }while(0) #define REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 4: E2_DIR_WRITE( INVERT_E2_DIR); break; case 5: E2_DIR_WRITE(!INVERT_E2_DIR); break; \ - case 6: E3_DIR_WRITE(!INVERT_E3_DIR); } }while(0) + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 4: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; case 5: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; \ + case 6: E3_DIR_WRITE(DISABLED(INVERT_E3_DIR)); } }while(0) #elif EXTRUDERS > 5 #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else { E2_STEP_WRITE(V); } }while(0) #define NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 4: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 5: E2_DIR_WRITE( INVERT_E2_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 4: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; case 5: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; \ } }while(0) #define REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 4: E2_DIR_WRITE( INVERT_E2_DIR); break; case 5: E2_DIR_WRITE(!INVERT_E2_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 4: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; case 5: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; \ } }while(0) #elif EXTRUDERS > 4 #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else { E2_STEP_WRITE(V); } }while(0) #define NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 4: E2_DIR_WRITE(!INVERT_E2_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 4: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; \ } }while(0) #define REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 4: E2_DIR_WRITE( INVERT_E2_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 4: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; \ } }while(0) #elif EXTRUDERS > 3 #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else { E1_STEP_WRITE(V); } }while(0) #define NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ } }while(0) #define REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; case 3: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ } }while(0) #elif EXTRUDERS > 2 #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else { E1_STEP_WRITE(V); } }while(0) #define NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ } }while(0) #define REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \ - case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; \ + case 2: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ } }while(0) #else #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V) - #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) + #define NORM_E_DIR(E) do{ E0_DIR_WRITE(E ? ENABLED(INVERT_E0_DIR) : DISABLED(INVERT_E0_DIR)); }while(0) + #define REV_E_DIR(E) do{ E0_DIR_WRITE(E ? DISABLED(INVERT_E0_DIR) : ENABLED(INVERT_E0_DIR)); }while(0) #endif #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) + #define NORM_E_DIR(E) E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)) + #define REV_E_DIR(E) E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)) #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) + #define NORM_E_DIR(E) do{ E0_DIR_WRITE(TEST(E, 0) ? DISABLED(INVERT_E0_DIR): ENABLED(INVERT_E0_DIR)); }while(0) + #define REV_E_DIR(E) do{ E0_DIR_WRITE(TEST(E, 0) ? ENABLED(INVERT_E0_DIR): DISABLED(INVERT_E0_DIR)); }while(0) #elif E_STEPPERS > 1 @@ -557,16 +557,16 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset case 4: E4_STEP_WRITE(V); break; case 5: E5_STEP_WRITE(V); break; case 6: E6_STEP_WRITE(V); break; case 7: E7_STEP_WRITE(V); break; \ } }while(0) #define _NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \ - case 4: E4_DIR_WRITE(!INVERT_E4_DIR); break; case 5: E5_DIR_WRITE(!INVERT_E5_DIR); break; \ - case 6: E6_DIR_WRITE(!INVERT_E6_DIR); break; case 7: E7_DIR_WRITE(!INVERT_E7_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE(DISABLED(INVERT_E3_DIR)); break; \ + case 4: E4_DIR_WRITE(DISABLED(INVERT_E4_DIR)); break; case 5: E5_DIR_WRITE(DISABLED(INVERT_E5_DIR)); break; \ + case 6: E6_DIR_WRITE(DISABLED(INVERT_E6_DIR)); break; case 7: E7_DIR_WRITE(DISABLED(INVERT_E7_DIR)); break; \ } }while(0) #define _REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \ - case 4: E4_DIR_WRITE( INVERT_E4_DIR); break; case 5: E5_DIR_WRITE( INVERT_E5_DIR); break; \ - case 6: E6_DIR_WRITE( INVERT_E6_DIR); break; case 7: E7_DIR_WRITE( INVERT_E7_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE( ENABLED(INVERT_E3_DIR)); break; \ + case 4: E4_DIR_WRITE( ENABLED(INVERT_E4_DIR)); break; case 5: E5_DIR_WRITE( ENABLED(INVERT_E5_DIR)); break; \ + case 6: E6_DIR_WRITE( ENABLED(INVERT_E6_DIR)); break; case 7: E7_DIR_WRITE( ENABLED(INVERT_E7_DIR)); break; \ } }while(0) #elif E_STEPPERS > 6 @@ -576,16 +576,16 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset case 4: E4_STEP_WRITE(V); break; case 5: E5_STEP_WRITE(V); break; case 6: E6_STEP_WRITE(V); break; \ } }while(0) #define _NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \ - case 4: E4_DIR_WRITE(!INVERT_E4_DIR); break; case 5: E5_DIR_WRITE(!INVERT_E5_DIR); break; \ - case 6: E6_DIR_WRITE(!INVERT_E6_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE(DISABLED(INVERT_E3_DIR)); break; \ + case 4: E4_DIR_WRITE(DISABLED(INVERT_E4_DIR)); break; case 5: E5_DIR_WRITE(DISABLED(INVERT_E5_DIR)); break; \ + case 6: E6_DIR_WRITE(DISABLED(INVERT_E6_DIR)); break; \ } }while(0) #define _REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \ - case 4: E4_DIR_WRITE( INVERT_E4_DIR); break; case 5: E5_DIR_WRITE( INVERT_E5_DIR); break; \ - case 6: E6_DIR_WRITE( INVERT_E6_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE( ENABLED(INVERT_E3_DIR)); break; \ + case 4: E4_DIR_WRITE( ENABLED(INVERT_E4_DIR)); break; case 5: E5_DIR_WRITE( ENABLED(INVERT_E5_DIR)); break; \ + case 6: E6_DIR_WRITE( ENABLED(INVERT_E6_DIR)); break; \ } }while(0) #elif E_STEPPERS > 5 @@ -595,14 +595,14 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset case 4: E4_STEP_WRITE(V); break; case 5: E5_STEP_WRITE(V); break; \ } }while(0) #define _NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \ - case 4: E4_DIR_WRITE(!INVERT_E4_DIR); break; case 5: E5_DIR_WRITE(!INVERT_E5_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE(DISABLED(INVERT_E3_DIR)); break; \ + case 4: E4_DIR_WRITE(DISABLED(INVERT_E4_DIR)); break; case 5: E5_DIR_WRITE(DISABLED(INVERT_E5_DIR)); break; \ } }while(0) #define _REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \ - case 4: E4_DIR_WRITE( INVERT_E4_DIR); break; case 5: E5_DIR_WRITE( INVERT_E5_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE( ENABLED(INVERT_E3_DIR)); break; \ + case 4: E4_DIR_WRITE( ENABLED(INVERT_E4_DIR)); break; case 5: E5_DIR_WRITE( ENABLED(INVERT_E5_DIR)); break; \ } }while(0) #elif E_STEPPERS > 4 @@ -612,14 +612,14 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset case 4: E4_STEP_WRITE(V); break; \ } }while(0) #define _NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \ - case 4: E4_DIR_WRITE(!INVERT_E4_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE(DISABLED(INVERT_E3_DIR)); break; \ + case 4: E4_DIR_WRITE(DISABLED(INVERT_E4_DIR)); break; \ } }while(0) #define _REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \ - case 4: E4_DIR_WRITE( INVERT_E4_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE( ENABLED(INVERT_E3_DIR)); break; \ + case 4: E4_DIR_WRITE( ENABLED(INVERT_E4_DIR)); break; \ } }while(0) #elif E_STEPPERS > 3 @@ -628,25 +628,25 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); break; \ } }while(0) #define _NORM_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \ + case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE(DISABLED(INVERT_E3_DIR)); break; \ } }while(0) #define _REV_E_DIR(E) do{ switch (E) { \ - case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \ - case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \ + case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; \ + case 2: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); break; case 3: E3_DIR_WRITE( ENABLED(INVERT_E3_DIR)); break; \ } }while(0) #elif E_STEPPERS > 2 #define _E_STEP_WRITE(E,V) do{ switch (E) { case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); } }while(0) - #define _NORM_E_DIR(E) do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 2: E2_DIR_WRITE(!INVERT_E2_DIR); } }while(0) - #define _REV_E_DIR(E) do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; case 2: E2_DIR_WRITE( INVERT_E2_DIR); } }while(0) + #define _NORM_E_DIR(E) do{ switch (E) { case 0: E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); break; case 2: E2_DIR_WRITE(DISABLED(INVERT_E2_DIR)); } }while(0) + #define _REV_E_DIR(E) do{ switch (E) { case 0: E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); break; case 1: E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); break; case 2: E2_DIR_WRITE( ENABLED(INVERT_E2_DIR)); } }while(0) #else #define _E_STEP_WRITE(E,V) do{ if (E == 0) { E0_STEP_WRITE(V); } else { E1_STEP_WRITE(V); } }while(0) - #define _NORM_E_DIR(E) do{ if (E == 0) { E0_DIR_WRITE(!INVERT_E0_DIR); } else { E1_DIR_WRITE(!INVERT_E1_DIR); } }while(0) - #define _REV_E_DIR(E) do{ if (E == 0) { E0_DIR_WRITE( INVERT_E0_DIR); } else { E1_DIR_WRITE( INVERT_E1_DIR); } }while(0) + #define _NORM_E_DIR(E) do{ if (E == 0) { E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); } else { E1_DIR_WRITE(DISABLED(INVERT_E1_DIR)); } }while(0) + #define _REV_E_DIR(E) do{ if (E == 0) { E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); } else { E1_DIR_WRITE( ENABLED(INVERT_E1_DIR)); } }while(0) #endif #if HAS_DUPLICATION_MODE @@ -657,8 +657,8 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define _DUPE(N,T,V) E##N##_##T##_WRITE(V) #endif - #define NDIR(N) _DUPE(N,DIR,!INVERT_E##N##_DIR) - #define RDIR(N) _DUPE(N,DIR, INVERT_E##N##_DIR) + #define NDIR(N) _DUPE(N,DIR,DISABLED(INVERT_E##N##_DIR)) + #define RDIR(N) _DUPE(N,DIR, ENABLED(INVERT_E##N##_DIR)) #define E_STEP_WRITE(E,V) do{ if (extruder_duplication_enabled) { DUPE(STEP,V); } else _E_STEP_WRITE(E,V); }while(0) @@ -704,13 +704,13 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #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) + #define NORM_E_DIR(E) do{ E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)); E1_DIR_WRITE(DISABLED(INVERT_E0_DIR) ^ ENABLED(INVERT_E1_VS_E0_DIR)); }while(0) + #define REV_E_DIR(E) do{ E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)); E1_DIR_WRITE( ENABLED(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) - #define REV_E_DIR(E) E0_DIR_WRITE( INVERT_E0_DIR) + #define NORM_E_DIR(E) E0_DIR_WRITE(DISABLED(INVERT_E0_DIR)) + #define REV_E_DIR(E) E0_DIR_WRITE( ENABLED(INVERT_E0_DIR)) #else #define E_STEP_WRITE(E,V) NOOP diff --git a/Marlin/src/module/speed_lookuptable.h b/Marlin/src/module/stepper/speed_lookuptable.h similarity index 100% rename from Marlin/src/module/speed_lookuptable.h rename to Marlin/src/module/stepper/speed_lookuptable.h diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index ee156a198629..bf36f83cd872 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -493,7 +493,7 @@ enum StealthIndex : uint8_t { #endif #define _EN_ITEM(N) , E##N - enum TMCAxis : uint8_t { NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL }; + enum TMCAxis : uint8_t { MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL }; #undef _EN_ITEM void tmc_serial_begin() { @@ -1023,19 +1023,15 @@ void reset_trinamic_drivers() { // 2. For each axis in use, static_assert using a constexpr function, which counts the // number of matching/conflicting axis. If the value is not exactly 1, fail. +#define ALL_AXIS_NAMES X, X2, Y, Y2, Z, Z2, Z3, Z4, I, J, K, U, V, W, E0, E1, E2, E3, E4, E5, E6, E7 + #if ANY_AXIS_HAS(HW_SERIAL) // Hardware serial names are compared as strings, since actually resolving them cannot occur in a constexpr. // 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) } - 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(U), TMC_HW_DETAIL(V), TMC_HW_DETAIL(W), - 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) - }; + constexpr SanityHwSerialDetails sanity_tmc_hw_details[] = { MAPLIST(TMC_HW_DETAIL, ALL_AXIS_NAMES) }; // constexpr compatible string comparison constexpr bool str_eq_ce(const char * a, const char * b) { @@ -1053,24 +1049,14 @@ void reset_trinamic_drivers() { #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(I); SA_NO_TMC_HW_C(J); SA_NO_TMC_HW_C(K); SA_NO_TMC_HW_C(U); SA_NO_TMC_HW_C(V); SA_NO_TMC_HW_C(W); - 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); + MAP(SA_NO_TMC_HW_C, ALL_AXIS_NAMES) #endif #if ANY_AXIS_HAS(SW_SERIAL) struct SanitySwSerialDetails { int32_t txpin; int32_t rxpin; uint32_t address; }; #define TMC_SW_DETAIL_ARGS(A) TERN(A##_HAS_SW_SERIAL, A##_SERIAL_TX_PIN, -1), TERN(A##_HAS_SW_SERIAL, A##_SERIAL_RX_PIN, -1), TERN0(A##_HAS_SW_SERIAL, A##_SLAVE_ADDRESS) - #define TMC_SW_DETAIL(A) TMC_SW_DETAIL_ARGS(A) - constexpr SanitySwSerialDetails sanity_tmc_sw_details[] = { - 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(U), TMC_SW_DETAIL(V), TMC_SW_DETAIL(W), - 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) - }; + #define TMC_SW_DETAIL(A) { TMC_SW_DETAIL_ARGS(A) } + constexpr SanitySwSerialDetails sanity_tmc_sw_details[] = { MAPLIST(TMC_SW_DETAIL, ALL_AXIS_NAMES) }; constexpr bool sc_sw_done(size_t start, size_t end) { return start == end; } constexpr bool sc_sw_skip(int32_t txpin) { return txpin < 0; } @@ -1083,11 +1069,7 @@ 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(I); SA_NO_TMC_SW_C(J); SA_NO_TMC_SW_C(K); SA_NO_TMC_SW_C(U); SA_NO_TMC_SW_C(V); SA_NO_TMC_SW_C(W); - 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); + MAP(SA_NO_TMC_SW_C, ALL_AXIS_NAMES) #endif #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 9cadcdc84e74..65b79d8bc464 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -71,6 +71,10 @@ #include "../libs/nozzle.h" #endif +#if LASER_SAFETY_TIMEOUT_MS > 0 + #include "../feature/spindle_laser.h" +#endif + // MAX TC related macros #define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) #define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) @@ -178,7 +182,7 @@ #include "tool_change.h" #endif -#if USE_BEEPER +#if HAS_BEEPER #include "../libs/buzzer.h" #endif @@ -914,13 +918,13 @@ volatile bool Temperature::raw_temps_ready = false; MPC_t &constants = hotend.constants; // Move to center of bed, just above bed height and cool with max fan + gcode.home_all_axes(true); disable_all_heaters(); #if HAS_FAN zero_fan_speeds(); set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 255); planner.sync_fan_speeds(fan_speed); #endif - gcode.home_all_axes(true); const xyz_pos_t tuningpos = MPC_TUNING_POS; do_blocking_move_to(tuningpos); @@ -994,7 +998,7 @@ volatile bool Temperature::raw_temps_ready = false; float asymp_temp = (t2 * t2 - t1 * t3) / (2 * t2 - t1 - t3), block_responsiveness = -log((t2 - asymp_temp) / (t1 - asymp_temp)) / (sample_distance * (sample_count >> 1)); - constants.ambient_xfer_coeff_fan0 = constants.heater_power * MPC_MAX / 255 / (asymp_temp - ambient_temp); + constants.ambient_xfer_coeff_fan0 = constants.heater_power * (MPC_MAX) / 255 / (asymp_temp - ambient_temp); constants.fan255_adjustment = 0.0f; constants.block_heat_capacity = constants.ambient_xfer_coeff_fan0 / block_responsiveness; constants.sensor_responsiveness = block_responsiveness / (1.0f - (ambient_temp - asymp_temp) * exp(-block_responsiveness * t1_time) / (t1 - asymp_temp)); @@ -1058,7 +1062,7 @@ volatile bool Temperature::raw_temps_ready = false; #endif // Calculate a new and better asymptotic temperature and re-evaluate the other constants - asymp_temp = ambient_temp + constants.heater_power / constants.ambient_xfer_coeff_fan0; + asymp_temp = ambient_temp + constants.heater_power * (MPC_MAX) / 255 / constants.ambient_xfer_coeff_fan0; block_responsiveness = -log((t2 - asymp_temp) / (t1 - asymp_temp)) / (sample_distance * (sample_count >> 1)); constants.block_heat_capacity = constants.ambient_xfer_coeff_fan0 / block_responsiveness; constants.sensor_responsiveness = block_responsiveness / (1.0f - (ambient_temp - asymp_temp) * exp(-block_responsiveness * t1_time) / (t1 - asymp_temp)); @@ -1224,18 +1228,14 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { marlin_state = MF_KILLED; thermalManager.disable_all_heaters(); - #if USE_BEEPER + #if HAS_BEEPER for (uint8_t i = 20; i--;) { - WRITE(BEEPER_PIN, HIGH); - delay(25); - watchdog_refresh(); - WRITE(BEEPER_PIN, LOW); - delay(40); - watchdog_refresh(); - delay(40); - watchdog_refresh(); + hal.watchdog_refresh(); + buzzer.click(25); + delay(80); + hal.watchdog_refresh(); } - WRITE(BEEPER_PIN, HIGH); + buzzer.on(); #endif #if ENABLED(NOZZLE_PARK_FEATURE) if (!homing_needed_error()) { @@ -1278,7 +1278,7 @@ void Temperature::_temp_error(const heater_id_t heater_id, FSTR_P const serial_m } disable_all_heaters(); // always disable (even for bogus temp) - watchdog_refresh(); + hal.watchdog_refresh(); #if BOGUS_TEMPERATURE_GRACE_PERIOD const millis_t ms = millis(); @@ -1318,104 +1318,101 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { } #if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) - bool Temperature::pid_debug_flag; // = 0 + #define HAS_PID_DEBUG 1 + bool Temperature::pid_debug_flag; // = false #endif -#if HAS_HOTEND +#if HAS_PID_HEATING - float Temperature::get_pid_output_hotend(const uint8_t E_NAME) { - const uint8_t ee = HOTEND_INDEX; - #if ENABLED(PIDTEMP) - #if DISABLED(PID_OPENLOOP) - static hotend_pid_t work_pid[HOTENDS]; - static float temp_iState[HOTENDS] = { 0 }, - temp_dState[HOTENDS] = { 0 }; - static Flags pid_reset; - const float pid_error = temp_hotend[ee].target - temp_hotend[ee].celsius; - - float pid_output; - - if (temp_hotend[ee].target == 0 - || pid_error < -(PID_FUNCTIONAL_RANGE) - || TERN0(HEATER_IDLE_HANDLER, heater_idle[ee].timed_out) - ) { - pid_output = 0; - pid_reset.set(ee); + template + class PIDRunner { + public: + TT &tempinfo; + __typeof__(TT::pid) work_pid{0}; + float temp_iState = 0, temp_dState = 0; + bool pid_reset = true; + + PIDRunner(TT &t) : tempinfo(t) { } + + float get_pid_output() { + + #if ENABLED(PID_OPENLOOP) + + return constrain(tempinfo.target, 0, MAX_POW); + + #else // !PID_OPENLOOP + + const float pid_error = tempinfo.target - tempinfo.celsius; + if (!tempinfo.target || pid_error < -(PID_FUNCTIONAL_RANGE)) { + pid_reset = true; + return 0; } else if (pid_error > PID_FUNCTIONAL_RANGE) { - pid_output = PID_MAX; - pid_reset.set(ee); + pid_reset = true; + return MAX_POW; } - else { - if (pid_reset[ee]) { - temp_iState[ee] = 0.0; - work_pid[ee].Kd = 0.0; - pid_reset.clear(ee); - } - work_pid[ee].Kd = work_pid[ee].Kd + PID_K2 * (PID_PARAM(Kd, ee) * (temp_dState[ee] - temp_hotend[ee].celsius) - work_pid[ee].Kd); - const float max_power_over_i_gain = float(PID_MAX) / PID_PARAM(Ki, ee) - float(MIN_POWER); - temp_iState[ee] = constrain(temp_iState[ee] + pid_error, 0, max_power_over_i_gain); - work_pid[ee].Kp = PID_PARAM(Kp, ee) * pid_error; - work_pid[ee].Ki = PID_PARAM(Ki, ee) * temp_iState[ee]; + if (pid_reset) { + pid_reset = false; + temp_iState = 0.0; + work_pid.Kd = 0.0; + } - pid_output = work_pid[ee].Kp + work_pid[ee].Ki + work_pid[ee].Kd + float(MIN_POWER); + const float max_power_over_i_gain = float(MAX_POW) / tempinfo.pid.Ki - float(MIN_POW); + temp_iState = constrain(temp_iState + pid_error, 0, max_power_over_i_gain); - #if ENABLED(PID_EXTRUSION_SCALING) - #if HOTENDS == 1 - constexpr bool this_hotend = true; - #else - const bool this_hotend = (ee == active_extruder); - #endif - work_pid[ee].Kc = 0; - if (this_hotend) { - const long e_position = stepper.position(E_AXIS); - if (e_position > pes_e_position) { - lpq[lpq_ptr] = e_position - pes_e_position; - pes_e_position = e_position; - } - else - lpq[lpq_ptr] = 0; + work_pid.Kp = tempinfo.pid.Kp * pid_error; + work_pid.Ki = tempinfo.pid.Ki * temp_iState; + work_pid.Kd = work_pid.Kd + PID_K2 * (tempinfo.pid.Kd * (temp_dState - tempinfo.celsius) - work_pid.Kd); - if (++lpq_ptr >= lpq_len) lpq_ptr = 0; - work_pid[ee].Kc = (lpq[lpq_ptr] * planner.mm_per_step[E_AXIS]) * PID_PARAM(Kc, ee); - pid_output += work_pid[ee].Kc; - } - #endif // PID_EXTRUSION_SCALING - #if ENABLED(PID_FAN_SCALING) - 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; - //pid_output += work_pid[ee].Ki * work_pid[ee].Kf - #endif // PID_FAN_SCALING - LIMIT(pid_output, 0, PID_MAX); - } - temp_dState[ee] = temp_hotend[ee].celsius; + temp_dState = tempinfo.celsius; - #else // PID_OPENLOOP + return constrain(work_pid.Kp + work_pid.Ki + work_pid.Kd + float(MIN_POW), 0, MAX_POW); - const float pid_output = constrain(temp_hotend[ee].target, 0, PID_MAX); + #endif // !PID_OPENLOOP + } - #endif // PID_OPENLOOP + FORCE_INLINE void debug(const_celsius_float_t c, const_float_t pid_out, FSTR_P const name=nullptr, const int8_t index=-1) { + if (TERN0(HAS_PID_DEBUG, thermalManager.pid_debug_flag)) { + SERIAL_ECHO_START(); + if (name) SERIAL_ECHOLNF(name); + if (index >= 0) SERIAL_ECHO(index); + SERIAL_ECHOLNPGM( + STR_PID_DEBUG_INPUT, c, + STR_PID_DEBUG_OUTPUT, pid_out + #if DISABLED(PID_OPENLOOP) + , "pTerm", work_pid.Kp, "iTerm", work_pid.Ki, "dTerm", work_pid.Kd + #endif + ); + } + } + }; + +#endif // HAS_PID_HEATING + +#if HAS_HOTEND + + float Temperature::get_pid_output_hotend(const uint8_t E_NAME) { + const uint8_t ee = HOTEND_INDEX; + + #if ENABLED(PIDTEMP) + + typedef PIDRunner PIDRunnerHotend; + + static PIDRunnerHotend hotend_pid[HOTENDS] = { + #define _HOTENDPID(E) temp_hotend[E], + REPEAT(HOTENDS, _HOTENDPID) + }; + + const float pid_output = hotend_pid[ee].get_pid_output(); #if ENABLED(PID_DEBUG) - if (ee == active_extruder && pid_debug_flag) { - 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 - ); - } + if (ee == active_extruder) + hotend_pid[ee].debug(temp_hotend[ee].celsius, pid_output, F("E"), ee); #endif #elif ENABLED(MPCTEMP) + MPCHeaterInfo &hotend = temp_hotend[ee]; MPC_t &constants = hotend.constants; @@ -1446,7 +1443,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { if (fabs(e_speed) > planner.settings.max_feedrate_mm_s[E_AXIS]) mpc_e_position = e_position; else if (e_speed > 0.0f) { // Ignore retract/recover moves - ambient_xfer_coeff += e_speed * FILAMENT_HEAT_CAPACITY_PERMM; + ambient_xfer_coeff += e_speed * constants.filament_heat_capacity_permm; mpc_e_position = e_position; } } @@ -1497,7 +1494,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #else // No PID or MPC enabled const bool is_idling = TERN0(HEATER_IDLE_HANDLER, heater_idle[ee].timed_out); - const float pid_output = (!is_idling && temp_hotend[ee].celsius < temp_hotend[ee].target) ? BANG_MAX : 0; + const float pid_output = (!is_idling && temp_hotend[ee].is_below_target()) ? BANG_MAX : 0; #endif @@ -1509,61 +1506,9 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #if ENABLED(PIDTEMPBED) float Temperature::get_pid_output_bed() { - - #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_BED_POWER) / temp_bed.pid.Ki - float(MIN_BED_POWER), - pid_error = temp_bed.target - temp_bed.celsius; - - if (!temp_bed.target || pid_error < -(PID_FUNCTIONAL_RANGE)) { - pid_output = 0; - pid_reset = true; - } - else if (pid_error > PID_FUNCTIONAL_RANGE) { - pid_output = MAX_BED_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_bed.pid.Kp * pid_error; - work_pid.Ki = temp_bed.pid.Ki * temp_iState; - work_pid.Kd = work_pid.Kd + PID_K2 * (temp_bed.pid.Kd * (temp_dState - temp_bed.celsius) - work_pid.Kd); - - temp_dState = temp_bed.celsius; - - pid_output = constrain(work_pid.Kp + work_pid.Ki + work_pid.Kd + float(MIN_BED_POWER), 0, MAX_BED_POWER); - } - - #else // PID_OPENLOOP - - const float pid_output = constrain(temp_bed.target, 0, MAX_BED_POWER); - - #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 - + static PIDRunner bed_pid(temp_bed); + const float pid_output = bed_pid.get_pid_output(); + TERN_(PID_BED_DEBUG, bed_pid.debug(temp_bed.celsius, pid_output, F("(Bed)"))); return pid_output; } @@ -1572,114 +1517,17 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #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_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 - #endif - ); - } - #endif - + static PIDRunner chamber_pid(temp_chamber); + const float pid_output = chamber_pid.get_pid_output(); + TERN_(PID_CHAMBER_DEBUG, chamber_pid.debug(temp_chamber.celsius, pid_output, F("(Chamber)"))); return pid_output; } #endif // PIDTEMPCHAMBER -/** - * Manage heating activities for extruder hot-ends and a heated bed - * - Acquire updated temperature readings - * - Also resets the watchdog timer - * - Invoke thermal runaway protection - * - Manage extruder auto-fan - * - Apply filament width to the extrusion rate (may move) - * - 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! - - static bool no_reentry = false; // Prevent recursion - if (no_reentry) return; - REMEMBER(mh, no_reentry, true); - - #if ENABLED(EMERGENCY_PARSER) - if (emergency_parser.killed_by_M112) kill(FPSTR(M112_KILL_STR), nullptr, true); - - if (emergency_parser.quickstop_by_M410) { - emergency_parser.quickstop_by_M410 = false; // quickstop_stepper may call idle so clear this now! - quickstop_stepper(); - } - #endif - - if (!updateTemperaturesIfReady()) return; // Will also reset the watchdog if temperatures are ready - - #if DISABLED(IGNORE_THERMOCOUPLE_ERRORS) - #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 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 - #else - #warning "Safety Alert! Disable IGNORE_THERMOCOUPLE_ERRORS for the final build!" - #endif - - millis_t ms = millis(); - - #if HAS_HOTEND +#if HAS_HOTEND + void Temperature::manage_hotends(const millis_t &ms) { HOTEND_LOOP() { #if ENABLED(THERMAL_PROTECTION_HOTENDS) if (degHotend(e) > temp_range[e].maxtemp) max_temp_error((heater_id_t)e); @@ -1707,25 +1555,13 @@ void Temperature::manage_heater() { #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)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET), F(STR_REDUNDANCY), GET_TEXT_F(MSG_ERR_REDUNDANT_TEMP)); - #endif - - // Manage extruder auto fans and/or read fan tachometers - TERN_(HAS_FAN_LOGIC, manage_extruder_fans(ms)); +#endif // HAS_HOTEND - /** - * Dynamically set the volumetric multiplier based - * on the delayed Filament Width measurement. - */ - TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_volumetric()); +#if HAS_HEATED_BED - #if HAS_HEATED_BED + void Temperature::manage_heated_bed(const millis_t &ms) { #if ENABLED(THERMAL_PROTECTION_BED) if (degBed() > BED_MAXTEMP) max_temp_error(H_BED); @@ -1770,9 +1606,7 @@ void Temperature::manage_heater() { #if HEATER_IDLE_HANDLER if (heater_idle[IDLE_INDEX_BED].timed_out) { temp_bed.soft_pwm_amount = 0; - #if DISABLED(PIDTEMPBED) - WRITE_HEATER_BED(LOW); - #endif + if (DISABLED(PIDTEMPBED)) WRITE_HEATER_BED(LOW); } else #endif @@ -1785,10 +1619,10 @@ void Temperature::manage_heater() { #if ENABLED(BED_LIMIT_SWITCHING) if (temp_bed.celsius >= temp_bed.target + BED_HYSTERESIS) temp_bed.soft_pwm_amount = 0; - else if (temp_bed.celsius <= temp_bed.target - (BED_HYSTERESIS)) + else if (temp_bed.is_below_target(-(BED_HYSTERESIS) + 1)) temp_bed.soft_pwm_amount = MAX_BED_POWER >> 1; #else // !PIDTEMPBED && !BED_LIMIT_SWITCHING - temp_bed.soft_pwm_amount = temp_bed.celsius < temp_bed.target ? MAX_BED_POWER >> 1 : 0; + temp_bed.soft_pwm_amount = temp_bed.is_below_target() ? MAX_BED_POWER >> 1 : 0; #endif } else { @@ -1799,10 +1633,13 @@ void Temperature::manage_heater() { } } while (false); + } - #endif // HAS_HEATED_BED +#endif // HAS_HEATED_BED - #if HAS_HEATED_CHAMBER +#if HAS_HEATED_CHAMBER + + void Temperature::manage_heated_chamber(const millis_t &ms) { #ifndef CHAMBER_CHECK_INTERVAL #define CHAMBER_CHECK_INTERVAL 1000UL @@ -1881,7 +1718,7 @@ void Temperature::manage_heater() { #endif #if ENABLED(CHAMBER_VENT) flag_chamber_excess_heat = false; - MOVE_SERVO(CHAMBER_VENT_SERVO_NR, 90); + servo[CHAMBER_VENT_SERVO_NR].move(90); #endif } #endif @@ -1897,20 +1734,20 @@ void Temperature::manage_heater() { 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); + if (!flag_chamber_off) servo[CHAMBER_VENT_SERVO_NR].move(temp_chamber.is_below_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)) + else if (temp_chamber.is_below_target(-(TEMP_CHAMBER_HYSTERESIS) + 1)) 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; + temp_chamber.soft_pwm_amount = temp_chamber.is_below_target() ? (MAX_CHAMBER_POWER) >> 1 : 0; #endif #if ENABLED(CHAMBER_VENT) - if (!flag_chamber_off) MOVE_SERVO(CHAMBER_VENT_SERVO_NR, 0); + if (!flag_chamber_off) servo[CHAMBER_VENT_SERVO_NR].move(0); #endif } } @@ -1923,10 +1760,13 @@ void Temperature::manage_heater() { 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 +#endif // HAS_HEATED_CHAMBER - #if HAS_COOLER +#if HAS_COOLER + + void Temperature::manage_cooler(const millis_t &ms) { #ifndef COOLER_CHECK_INTERVAL #define COOLER_CHECK_INTERVAL 2000UL @@ -1984,15 +1824,90 @@ void Temperature::manage_heater() { #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_COOLER +#endif // HAS_COOLER + +/** + * Manage heating activities for extruder hot-ends and a heated bed + * - Acquire updated temperature readings + * - Also resets the watchdog timer + * - Invoke thermal runaway protection + * - Manage extruder auto-fan + * - Apply filament width to the extrusion rate (may move) + * - Update the heated bed PID output value + */ +void Temperature::task() { + if (marlin_state == MF_INITIALIZING) return hal.watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog! + + static bool no_reentry = false; // Prevent recursion + if (no_reentry) return; + REMEMBER(mh, no_reentry, true); + + #if ENABLED(EMERGENCY_PARSER) + if (emergency_parser.killed_by_M112) kill(FPSTR(M112_KILL_STR), nullptr, true); + + if (emergency_parser.quickstop_by_M410) { + emergency_parser.quickstop_by_M410 = false; // quickstop_stepper may call idle so clear this now! + quickstop_stepper(); + } + #endif + + if (!updateTemperaturesIfReady()) return; // Will also reset the watchdog if temperatures are ready + + #if DISABLED(IGNORE_THERMOCOUPLE_ERRORS) + #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 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 + #else + #warning "Safety Alert! Disable IGNORE_THERMOCOUPLE_ERRORS for the final build!" + #endif + + const millis_t ms = millis(); + + // Handle Hotend Temp Errors, Heating Watch, etc. + TERN_(HAS_HOTEND, manage_hotends(ms)); + + #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)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET), F(STR_REDUNDANCY), GET_TEXT_F(MSG_ERR_REDUNDANT_TEMP)); + #endif + + // Manage extruder auto fans and/or read fan tachometers + TERN_(HAS_FAN_LOGIC, manage_extruder_fans(ms)); + + /** + * Dynamically set the volumetric multiplier based + * on the delayed Filament Width measurement. + */ + TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_volumetric()); + + // Handle Bed Temp Errors, Heating Watch, etc. + TERN_(HAS_HEATED_BED, manage_heated_bed(ms)); + + // Handle Heated Chamber Temp Errors, Heating Watch, etc. + TERN_(HAS_HEATED_CHAMBER, manage_heated_chamber(ms)); + + // Handle Cooler Temp Errors, Cooling Watch, etc. + TERN_(HAS_COOLER, manage_cooler(ms)); #if ENABLED(LASER_COOLANT_FLOW_METER) cooler.flowmeter_task(ms); #if ENABLED(FLOWMETER_SAFETY) - if (cutter.enabled() && cooler.check_flow_too_low()) { + if (cooler.check_flow_too_low()) { + TERN_(HAS_DISPLAY, if (cutter.enabled()) ui.flow_fault()); cutter.disable(); - TERN_(HAS_DISPLAY, ui.flow_fault()); + cutter.cutter_mode = CUTTER_MODE_ERROR; // Immediately kill stepper inline power output } #endif #endif @@ -2391,7 +2306,7 @@ void Temperature::manage_heater() { */ void Temperature::updateTemperaturesFromRawValues() { - watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt + hal.watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].setraw(READ_MAX_TC(0))); TERN_(TEMP_SENSOR_1_IS_MAX_TC, temp_hotend[1].setraw(READ_MAX_TC(1))); @@ -2479,7 +2394,7 @@ void Temperature::updateTemperaturesFromRawValues() { /** * Initialize the temperature manager * - * The manager is implemented by periodic calls to manage_heater() + * The manager is implemented by periodic calls to task() * * - Init (and disable) SPI thermocouples like MAX6675 and MAX31865 * - Disable RUMBA JTAG to accommodate a thermocouple extension @@ -2709,13 +2624,15 @@ void Temperature::init() { #if HAS_HOTEND #define _TEMP_MIN_E(NR) do{ \ - 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))); \ + const celsius_t tmin_tmp = TERN(TEMP_SENSOR_##NR##_IS_CUSTOM, 0, int16_t(pgm_read_word(&TEMPTABLE_##NR [TEMP_SENSOR_##NR##_MINTEMP_IND].celsius))), \ + tmin = _MAX(HEATER_##NR##_MINTEMP, tmin_tmp); \ 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 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)); \ + const celsius_t tmax_tmp = TERN(TEMP_SENSOR_##NR##_IS_CUSTOM, 2000, int16_t(pgm_read_word(&TEMPTABLE_##NR [TEMP_SENSOR_##NR##_MAXTEMP_IND].celsius)) - 1), \ + tmax = _MIN(HEATER_##NR##_MAXTEMP, tmax_tmp); \ 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); \ @@ -3109,7 +3026,7 @@ void Temperature::disable_all_heaters() { static millis_t next_max_tc_ms[MAX_TC_COUNT] = { 0 }; // Return last-read value between readings - millis_t ms = millis(); + const millis_t ms = millis(); if (PENDING(ms, next_max_tc_ms[hindex])) return THERMO_TEMP(hindex); @@ -3332,6 +3249,7 @@ class SoftPWM { /** * Handle various ~1kHz tasks associated with temperature + * - Check laser safety timeout * - Heater PWM (~1kHz with scaler) * - LCD Button polling (~500Hz) * - Start / Read one ADC sensor @@ -3341,6 +3259,14 @@ class SoftPWM { */ void Temperature::isr() { + // Shut down the laser if steppers are inactive for > LASER_SAFETY_TIMEOUT_MS ms + #if LASER_SAFETY_TIMEOUT_MS > 0 + if (cutter.last_power_applied && ELAPSED(millis(), gcode.previous_move_ms + (LASER_SAFETY_TIMEOUT_MS))) { + cutter.power = 0; // Prevent planner idle from re-enabling power + cutter.apply_power(0); + } + #endif + static int8_t temp_count = -1; static ADCSensorState adc_sensor_state = StartupDelay; static uint8_t pwm_count = _BV(SOFT_PWM_SCALE); @@ -3408,16 +3334,18 @@ void Temperature::isr() { _PWM_MOD(COOLER, soft_pwm_cooler, temp_cooler); #endif - #if BOTH(USE_CONTROLLER_FAN, FAN_SOFT_PWM) - WRITE(CONTROLLER_FAN_PIN, soft_pwm_controller.add(pwm_mask, soft_pwm_controller_speed)); - #endif - #if ENABLED(FAN_SOFT_PWM) + + #if ENABLED(USE_CONTROLLER_FAN) + WRITE(CONTROLLER_FAN_PIN, soft_pwm_controller.add(pwm_mask, soft_pwm_controller_speed)); + #endif + #define _FAN_PWM(N) do{ \ uint8_t &spcf = soft_pwm_count_fan[N]; \ spcf = (spcf & pwm_mask) + (soft_pwm_amount_fan[N] >> 1); \ WRITE_FAN(N, spcf > pwm_mask ? HIGH : LOW); \ }while(0) + #if HAS_FAN0 _FAN_PWM(0); #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index f54cd0334bf2..80d15ce39e4a 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -96,13 +96,14 @@ hotend_pid_t; #if ENABLED(MPCTEMP) typedef struct { - float heater_power; // M306 P - float block_heat_capacity; // M306 C - float sensor_responsiveness; // M306 R - float ambient_xfer_coeff_fan0; // M306 A + float heater_power; // M306 P + float block_heat_capacity; // M306 C + float sensor_responsiveness; // M306 R + float ambient_xfer_coeff_fan0; // M306 A #if ENABLED(MPC_INCLUDE_FAN) - float fan255_adjustment; // M306 F + float fan255_adjustment; // M306 F #endif + float filament_heat_capacity_permm; // M306 H } MPC_t; #endif @@ -231,6 +232,7 @@ typedef struct TempInfo { typedef struct HeaterInfo : public TempInfo { celsius_t target; uint8_t soft_pwm_amount; + bool is_below_target(const celsius_t offs=0) const { return (celsius < (target + offs)); } } heater_info_t; // A heater with PID stabilization @@ -714,9 +716,9 @@ class Temperature { static void readings_ready(); /** - * Call periodically to manage heaters + * Call periodically to manage heaters and keep the watchdog fed */ - static void manage_heater() _O2; // Added _O2 to work around a compiler error + static void task(); /** * Preheating hotends @@ -806,6 +808,8 @@ class Temperature { #endif } + static void manage_hotends(const millis_t &ms); + #endif // HAS_HOTEND #if HAS_HEATED_BED @@ -818,6 +822,9 @@ class Temperature { static celsius_t degTargetBed() { return temp_bed.target; } static bool isHeatingBed() { return temp_bed.target > temp_bed.celsius; } static bool isCoolingBed() { return temp_bed.target < temp_bed.celsius; } + static bool degBedNear(const celsius_t temp) { + return ABS(wholeDegBed() - temp) < (TEMP_BED_HYSTERESIS); + } // Start watching the Bed to make sure it's really heating up static void start_watching_bed() { TERN_(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())); } @@ -834,9 +841,7 @@ class Temperature { static void wait_for_bed_heating(); - static bool degBedNear(const celsius_t temp) { - return ABS(wholeDegBed() - temp) < (TEMP_BED_HYSTERESIS); - } + static void manage_heated_bed(const millis_t &ms); #endif // HAS_HEATED_BED @@ -862,6 +867,7 @@ class Temperature { static bool isHeatingChamber() { return temp_chamber.target > temp_chamber.celsius; } static bool isCoolingChamber() { return temp_chamber.target < temp_chamber.celsius; } static bool wait_for_chamber(const bool no_wait_for_cooling=true); + static void manage_heated_chamber(const millis_t &ms); #endif #endif @@ -885,6 +891,7 @@ class Temperature { static bool isLaserHeating() { return temp_cooler.target > temp_cooler.celsius; } static bool isLaserCooling() { return temp_cooler.target < temp_cooler.celsius; } static bool wait_for_cooler(const bool no_wait_for_cooling=true); + static void manage_cooler(const millis_t &ms); #endif #endif diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index e2f1443048ed..4b292c92f98b 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -116,7 +116,7 @@ void move_extruder_servo(const uint8_t e) { planner.synchronize(); if ((EXTRUDERS & 1) && e < EXTRUDERS - 1) { - MOVE_SERVO(_SERVO_NR(e), servo_angles[_SERVO_NR(e)][e & 1]); + servo[_SERVO_NR(e)].move(servo_angles[_SERVO_NR(e)][e & 1]); safe_delay(500); } } @@ -131,7 +131,7 @@ constexpr int8_t sns_index[2] = { SWITCHING_NOZZLE_SERVO_NR, SWITCHING_NOZZLE_E1_SERVO_NR }; constexpr int16_t sns_angles[2] = SWITCHING_NOZZLE_SERVO_ANGLES; planner.synchronize(); - MOVE_SERVO(sns_index[e], sns_angles[angle_index]); + servo[sns_index[e]].move(sns_angles[angle_index]); safe_delay(500); } @@ -142,7 +142,7 @@ void move_nozzle_servo(const uint8_t angle_index) { planner.synchronize(); - MOVE_SERVO(SWITCHING_NOZZLE_SERVO_NR, servo_angles[SWITCHING_NOZZLE_SERVO_NR][angle_index]); + servo[SWITCHING_NOZZLE_SERVO_NR].move(servo_angles[SWITCHING_NOZZLE_SERVO_NR][angle_index]); safe_delay(500); } @@ -443,7 +443,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. 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]); + servo[SWITCHING_TOOLHEAD_SERVO_NR].move(swt_angles[locked ? 0 : 1]); #elif PIN_EXISTS(SWT_SOLENOID) OUT_WRITE(SWT_SOLENOID_PIN, locked); gcode.dwell(10); diff --git a/Marlin/src/pins/esp32/pins_E4D.h b/Marlin/src/pins/esp32/pins_E4D.h index 02a5fe4e33aa..d12b5276b7be 100644 --- a/Marlin/src/pins/esp32/pins_E4D.h +++ b/Marlin/src/pins/esp32/pins_E4D.h @@ -31,28 +31,23 @@ #include "env_validate.h" #if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "E4d@box only supports one E Stepper. Comment out this line to continue." + #error "E4d@box only supports 1 E stepper." #elif HAS_MULTI_HOTEND - #error "E4d@box only supports one hotend / E-stepper. Comment out this line to continue." + #error "E4d@box only supports 1 hotend / E stepper." #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_WS 23 +#define I2S_BCK 22 #define I2S_DATA 21 // diff --git a/Marlin/src/pins/esp32/pins_ENWI_ESPNP.h b/Marlin/src/pins/esp32/pins_ENWI_ESPNP.h index aff7f742edf9..80923d972deb 100644 --- a/Marlin/src/pins/esp32/pins_ENWI_ESPNP.h +++ b/Marlin/src/pins/esp32/pins_ENWI_ESPNP.h @@ -35,9 +35,11 @@ // I2S (steppers & other output-only pins) // #define I2S_STEPPER_STREAM -#define I2S_WS 17 -#define I2S_BCK 22 -#define I2S_DATA 21 +#if ENABLED(I2S_STEPPER_STREAM) + #define I2S_WS 17 + #define I2S_BCK 22 + #define I2S_DATA 21 +#endif // // Servos diff --git a/Marlin/src/pins/esp32/pins_ESP32.h b/Marlin/src/pins/esp32/pins_ESP32.h index 6578770ba0e2..266de7e9f60e 100644 --- a/Marlin/src/pins/esp32/pins_ESP32.h +++ b/Marlin/src/pins/esp32/pins_ESP32.h @@ -33,9 +33,11 @@ // I2S (steppers & other output-only pins) // #define I2S_STEPPER_STREAM -#define I2S_WS 25 -#define I2S_BCK 26 -#define I2S_DATA 27 +#if ENABLED(I2S_STEPPER_STREAM) + #define I2S_WS 25 + #define I2S_BCK 26 + #define I2S_DATA 27 +#endif // // Limit Switches diff --git a/Marlin/src/pins/esp32/pins_ESPA_common.h b/Marlin/src/pins/esp32/pins_ESPA_common.h index 2fcacb3002b4..ca949cdf9716 100644 --- a/Marlin/src/pins/esp32/pins_ESPA_common.h +++ b/Marlin/src/pins/esp32/pins_ESPA_common.h @@ -32,14 +32,6 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #endif -// -// Disable I2S stepper stream, by default -// -#undef I2S_STEPPER_STREAM -#undef I2S_WS -#undef I2S_BCK -#undef I2S_DATA - // // Limit Switches // diff --git a/Marlin/src/pins/esp32/pins_FYSETC_E4.h b/Marlin/src/pins/esp32/pins_FYSETC_E4.h index e75b6ece2820..7dc59979c8f1 100644 --- a/Marlin/src/pins/esp32/pins_FYSETC_E4.h +++ b/Marlin/src/pins/esp32/pins_FYSETC_E4.h @@ -31,9 +31,9 @@ #include "env_validate.h" #if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "FYSETC E4 only supports one E Stepper. Comment out this line to continue." + #error "FYSETC E4 only supports 1 E stepper." #elif HAS_MULTI_HOTEND - #error "FYSETC E4 only supports one hotend / E-stepper. Comment out this line to continue." + #error "FYSETC E4 only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "FYSETC_E4" diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 68b8ed4ac800..110c6f83ef85 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -31,15 +31,17 @@ #include "env_validate.h" #if EXTRUDERS > 2 || E_STEPPERS > 2 - #error "MKS ESP Nano only supports two E Steppers. Comment out this line to continue." + #error "MKS TinyBee supports up to 2 E steppers." #elif HOTENDS > 2 - #error "MKS ESP Nano only supports two hotend / E-stepper. Comment out this line to continue." + #error "MKS TinyBee supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS TinyBee" #define BOARD_WEBSITE_URL "https://github.com/makerbase-mks" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +// MAX_EXPANDER_BITS is defined for MKS TinyBee in HAL/ESP32/inc/Conditionals_adv.h + // // Servos // @@ -61,9 +63,6 @@ #define I2S_WS 26 #define I2S_BCK 25 #define I2S_DATA 27 - #if ENABLED(LIN_ADVANCE) - #error "I2S stream is currently incompatible with LIN_ADVANCE." - #endif #endif // @@ -116,17 +115,7 @@ // // ADC Reference Voltage // -#define ADC_REFERENCE_VOLTAGE 2.5 // 2.5V reference VDDA - -// -// MicroSD card -// -#define SD_MOSI_PIN 23 -#define SD_MISO_PIN 19 -#define SD_SCK_PIN 18 -#define SDSS 5 -#define SD_DETECT_PIN 34 // IO34 default is SD_DET signal (Jump to SDDET) -#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers +#define ADC_REFERENCE_VOLTAGE 2.565 // 2.5V reference VDDA /** * ------ ------ @@ -157,56 +146,48 @@ #define EXP2_09_PIN 18 #define EXP2_10_PIN 19 -#if HAS_WIRED_LCD +// +// MicroSD card +// +//#define SD_MOSI_PIN EXP2_05_PIN // uses esp32 default 23 +//#define SD_MISO_PIN EXP2_10_PIN // uses esp32 default 19 +//#define SD_SCK_PIN EXP2_09_PIN // uses esp32 default 18 +#define SDSS EXP2_07_PIN +#define SD_DETECT_PIN EXP2_04_PIN // IO34 default is SD_DET signal (Jump to SDDET) +#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers - #define BEEPER_PIN 149 - #define BTN_ENC 13 - #define LCD_PINS_ENABLE 21 - #define LCD_PINS_RS 4 - #define BTN_EN1 14 - #define BTN_EN2 12 +#if HAS_WIRED_LCD + #define BEEPER_PIN EXP1_10_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #define LCD_BACKLIGHT_PIN -1 - // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) - - //#define LCD_BACKLIGHT_PIN -1 - //#define LCD_RESET_PIN -1 - #define DOGLCD_A0 15 - #define DOGLCD_CS 16 - //#define DOGLCD_SCK 19 - //#define DOGLCD_MOSI 23 - - // Required for MKS_MINI_12864 with this board - //#define MKS_LCD12864B - - #elif ENABLED(MKS_MINI_12864_V3) - - #define LCD_PINS_DC EXP1_07_PIN + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define LCD_RESET_PIN -1 + #elif ENABLED(FYSETC_MINI_12864_2_1) + // MKS_MINI_12864_V3, BTT_MINI_12864_V1, FYSETC_MINI_12864_2_1 #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 LCD_PINS_DC - #define LCD_BACKLIGHT_PIN -1 + #define DOGLCD_A0 EXP1_07_PIN #define LCD_RESET_PIN EXP1_06_PIN #define NEOPIXEL_PIN EXP1_05_PIN - #define DOGLCD_MOSI EXP2_05_PIN - #define DOGLCD_SCK EXP2_09_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif - - #else // !MKS_MINI_12864 - - #define LCD_PINS_D4 0 + #else + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define LCD_PINS_D5 16 - #define LCD_PINS_D6 15 - #define LCD_PINS_D7 17 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #endif - #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 600 - - #endif // !MKS_MINI_12864 - + #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPA.h b/Marlin/src/pins/esp32/pins_MRR_ESPA.h index cc67bc025cec..e9e3db575896 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPA.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPA.h @@ -31,9 +31,9 @@ #include "env_validate.h" #if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "MRR ESPA only supports one E Stepper. Comment out this line to continue." + #error "MRR ESPA only supports 1 E stepper." #elif HAS_MULTI_HOTEND - #error "MRR ESPA only supports one hotend / E-stepper. Comment out this line to continue." + #error "MRR ESPA only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "MRR ESPA" diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPE.h b/Marlin/src/pins/esp32/pins_MRR_ESPE.h index 9b9b54e3aebe..f372de9e0110 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPE.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPE.h @@ -32,9 +32,9 @@ #include "env_validate.h" #if EXTRUDERS > 2 || E_STEPPERS > 2 - #error "MRR ESPE only supports two E Steppers. Comment out this line to continue." + #error "MRR ESPE supports up to 2 E steppers." #elif HAS_MULTI_HOTEND - #error "MRR ESPE only supports one hotend / E-stepper. Comment out this line to continue." + #error "MRR ESPE only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "MRR ESPE" @@ -52,11 +52,10 @@ // Enable I2S stepper stream // #define I2S_STEPPER_STREAM -#define I2S_WS 26 -#define I2S_BCK 25 -#define I2S_DATA 27 -#if ENABLED(LIN_ADVANCE) - #error "I2S stream is currently incompatible with LIN_ADVANCE." +#if ENABLED(I2S_STEPPER_STREAM) + #define I2S_WS 26 + #define I2S_BCK 25 + #define I2S_DATA 27 #endif // diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index e2efdfa4929b..7953f678fa48 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -54,7 +54,7 @@ #endif #ifndef MARLIN_EEPROM_SIZE - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 586fb14e8eb7..4ab5b109372f 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -223,7 +223,9 @@ #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ANET_FULL_GRAPHICS_LCD requires wiring modifications. See 'pins_BTT_SKR_V1_3.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. @@ -257,7 +259,9 @@ #elif ENABLED(WYH_L12864) - #error "CAUTION! WYH_L12864 requires wiring modifications. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! WYH_L12864 requires wiring modifications. See 'pins_BTT_SKR_V1_3.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. @@ -310,7 +314,7 @@ #define TFT_RESET_PIN EXP1_07_PIN #define TFT_BACKLIGHT_PIN EXP1_08_PIN - #define TFT_RST_PIN EXP2_04_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 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 df6ae8c01721..b50e8e578006 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -46,9 +46,9 @@ #endif #if ENABLED(I2C_EEPROM) - #define MARLIN_EEPROM_SIZE 0x8000 // 32Kb + #define MARLIN_EEPROM_SIZE 0x8000 // 32K #elif ENABLED(SDCARD_EEPROM_EMULATION) - #define MARLIN_EEPROM_SIZE 0x800 // 2Kb + #define MARLIN_EEPROM_SIZE 0x800 // 2K #endif // @@ -286,7 +286,9 @@ #elif HAS_WIRED_LCD #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ANET_FULL_GRAPHICS_LCD_ALT_WIRING requires wiring modifications. See 'pins_BTT_SKR_V1_4.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. @@ -318,7 +320,9 @@ #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ANET_FULL_GRAPHICS_LCD requires wiring modifications. See 'pins_BTT_SKR_V1_4.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index b08ac536b3d0..56d75a748cbc 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -307,7 +307,9 @@ #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ZONESTAR_LCD on REARM requires wiring modifications. NB. ADCs are not 5V tolerant. See 'pins_RAMPS_RE_ARM.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif #elif IS_TFTGLCD_PANEL 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 56ee7fa73235..090a2e40517e 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -35,7 +35,7 @@ // Onboard I2C EEPROM #define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x1000 // 4KB (AT24C32) +#define MARLIN_EEPROM_SIZE 0x1000 // 4K (AT24C32) // // Servos @@ -204,7 +204,9 @@ #define EXP1_10_PIN P2_08 #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI - #error "Ender-3 V2 display requires a custom cable with TX = P0_15, RX = P0_16. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! Ender-3 V2 display requires a custom cable with TX = P0_15, RX = P0_16. See 'pins_BTT_SKR_E3_TURBO.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo @@ -238,7 +240,9 @@ #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_E3_TURBO.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif #define LCD_PINS_RS EXP1_05_PIN #define LCD_PINS_ENABLE EXP1_09_PIN 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 7edfb9196fa2..4cff5d59e17d 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -36,10 +36,8 @@ // EEPROM, MKS SGEN_L V2.0 hardware has 4K EEPROM on the board // #if NO_EEPROM_SELECTED - //#define SDCARD_EEPROM_EMULATION - //#define I2C_EEPROM // AT24C32 - #define FLASH_EEPROM_EMULATION - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define I2C_EEPROM // AT24C32 + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // @@ -103,6 +101,12 @@ #define Z_MIN_PROBE_PIN P1_24 #endif +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN P1_28 // X+ +#define FIL_RUNOUT2_PIN P1_26 // Y+ + // // Steppers // @@ -203,6 +207,14 @@ #define TEMP_1_PIN P0_25_A2 // Analog Input A2 (TH2) #define TEMP_2_PIN P0_26_A3 // Analog Input A3 (P0.26, No pull up) +#if HOTENDS == 1 && !REDUNDANT_TEMP_MATCH(SOURCE, E1) + #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 // @@ -327,9 +339,10 @@ #define KILL_PIN -1 // NC #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI + #define TFT_CS_PIN EXP1_04_PIN - #define TFT_A0_PIN EXP1_03_PIN #define TFT_DC_PIN EXP1_03_PIN + #define TFT_A0_PIN TFT_DC_PIN #define TFT_MISO_PIN EXP2_10_PIN #define TFT_BACKLIGHT_PIN EXP1_08_PIN #define TFT_RESET_PIN EXP1_07_PIN diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h index 6f9e5e8e6c47..5f7a534d115b 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h @@ -135,17 +135,20 @@ // // LCD / Controller // -#define BEEPER_PIN 6 - -// Pins for DOGM SPI LCD Support -#define DOGLCD_A0 26 -#define DOGLCD_CS 24 -#define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h -#define DOGLCD_SCK -1 - -#define BTN_EN1 23 -#define BTN_EN2 25 -#define BTN_ENC 27 +#if HAS_WIRED_LCD + #define BEEPER_PIN 6 + + #define BTN_EN1 23 + #define BTN_EN2 25 + #define BTN_ENC 27 + + #if HAS_MARLINUI_U8GLIB + #define DOGLCD_A0 26 + #define DOGLCD_CS 24 + #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h + #define DOGLCD_SCK -1 + #endif +#endif // Hardware buttons for manual movement of XYZ #define SHIFT_OUT_PIN 19 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h index 137650eeed58..0aa0b59ca945 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h @@ -140,18 +140,20 @@ // // LCD / Controller // -#define BEEPER_PIN 16 - -// Pins for DOGM SPI LCD Support -#define DOGLCD_A0 39 -#define DOGLCD_CS 35 -#define DOGLCD_MOSI 48 -#define DOGLCD_SCK 49 - -// The encoder and click button -#define BTN_EN1 36 -#define BTN_EN2 34 -#define BTN_ENC 38 +#if HAS_WIRED_LCD + #define BEEPER_PIN 16 + + #define BTN_EN1 36 + #define BTN_EN2 34 + #define BTN_ENC 38 + + #if HAS_MARLINUI_U8GLIB + #define DOGLCD_A0 39 + #define DOGLCD_CS 35 + #define DOGLCD_MOSI 48 + #define DOGLCD_SCK 49 + #endif +#endif // Hardware buttons for manual movement of XYZ #define SHIFT_OUT_PIN 42 diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h b/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h index 6b22b4139b6d..e683d4dfda4b 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h @@ -27,9 +27,9 @@ #define BOARD_INFO_NAME "GT2560 V3.0 (MC2)" -#define X_MIN_PIN 22 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 26 -#define Y_MAX_PIN 28 +#define X_MIN_PIN 22 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 26 +#define Y_MAX_PIN 28 #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index dc9fa52af8e6..7ebef6e281cf 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Mega Controller supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "Mega Controller supports up to 2 hotends / E steppers." #endif #include "env_validate.h" diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index 13ffc9448640..3bcece400f96 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -149,8 +149,8 @@ #define MOSFET_1_PIN 6 // Plug EX1 Pin 1-2 -> PH3 #15 -> Logical 06 #define MOSFET_2_PIN 7 // Plug EX1 Pin 3-4 -> PH4 #16 -> Logical 07 -#define MOSFET_3_PIN 11 // Plug EX2 1-2 -> PB6 #24 -> Logical 11 -#define MOSFET_4_PIN 12 // Plug EX2 3-4 -> PB5 #25 -> Logical 12 +#define MOSFET_3_PIN 11 // Plug EX2 1-2 -> PB5 #24 -> Logical 11 +#define MOSFET_4_PIN 12 // Plug EX2 3-4 -> PB6 #25 -> Logical 12 #define MOSFET_5_PIN 45 // Plug HBD 1-2 -> PL4 #39 -> Logical 45 #define MOSFET_6_PIN 44 // Plug Extra 1-2 -> PL5 #40 -> Logical 44 (FET not soldered in all boards) @@ -166,19 +166,23 @@ #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN MOSFET_2_PIN #else - #define FAN_PIN MOSFET_2_PIN + #ifndef FAN_PIN + #define FAN_PIN MOSFET_2_PIN + #endif #endif // EX2 FAN (Automatic Fans are disabled by default in Configuration_adv.h - comment that out for auto fans) #ifndef E1_AUTO_FAN_PIN #define E1_AUTO_FAN_PIN MOSFET_4_PIN #else - #define FAN1_PIN MOSFET_4_PIN + #ifndef FAN1_PIN + #define FAN1_PIN MOSFET_4_PIN + #endif #endif // // Misc. Functions // -#define LED_PIN MOSFET_6_PIN // B7 +#define LED_PIN 13 // B7 #define CUTOFF_RESET_PIN 16 // H1 #define CUTOFF_TEST_PIN 17 // H0 #define CUTOFF_SR_CHECK_PIN 70 // G4 (TOSC1) diff --git a/Marlin/src/pins/mega/pins_MINITRONICS.h b/Marlin/src/pins/mega/pins_MINITRONICS.h index bbe746461eca..ec712a3b90e5 100644 --- a/Marlin/src/pins/mega/pins_MINITRONICS.h +++ b/Marlin/src/pins/mega/pins_MINITRONICS.h @@ -34,7 +34,7 @@ #if NOT_TARGET(__AVR_ATmega1281__) #error "Oops! Select 'Minitronics' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 - #error "Minitronics supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "Minitronics supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Minitronics v1.0/1.1" diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index 98f8da571940..f1062b413e83 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Overlord Controller supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "Overlord supports up to 2 hotends / E steppers." #endif #include "env_validate.h" diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 01e5ee41e383..2a29c66d8acc 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -464,14 +464,14 @@ #include "sam/pins_ARCHIM2.h" // SAM3X8E env:DUE_archim env:DUE_archim_debug #elif MB(ALLIGATOR) #include "sam/pins_ALLIGATOR_R2.h" // SAM3X8E env:DUE env:DUE_debug -#elif MB(ADSK) - #include "sam/pins_ADSK.h" // SAM3X8E env:DUE env:DUE_debug -#elif MB(PRINTRBOARD_G2) - #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 +#elif MB(PRINTRBOARD_G2) + #include "sam/pins_PRINTRBOARD_G2.h" // SAM3X8C env:DUE_USB +#elif MB(ADSK) + #include "sam/pins_ADSK.h" // SAM3X8C env:DUE env:DUE_debug // // STM32 ARM Cortex-M0 @@ -492,15 +492,15 @@ #elif MB(STM3R_MINI) #include "stm32f1/pins_STM3R_MINI.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VB) - #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple + #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(GTM32_PRO_VD) - #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple + #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(GTM32_MINI) - #include "stm32f1/pins_GTM32_MINI.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple + #include "stm32f1/pins_GTM32_MINI.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(GTM32_MINI_A30) - #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple + #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(GTM32_REV_B) - #include "stm32f1/pins_GTM32_REV_B.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple + #include "stm32f1/pins_GTM32_REV_B.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(MORPHEUS) #include "stm32f1/pins_MORPHEUS.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple #elif MB(CHITU3D) @@ -538,7 +538,7 @@ #elif MB(BTT_SKR_MINI_E3_V2_0) #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V3_0) - #include "stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h" // STM32G0 env:STM32G0B1RE_btt + #include "stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h" // STM32G0 env:STM32G0B1RE_btt env:STM32G0B1RE_btt_xfer #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) @@ -556,7 +556,7 @@ #elif MB(LONGER3D_LK) #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 + #include "stm32f1/pins_CCROBOT_MEEB_3DP.h" // STM32F1 env:STM32F103RC_meeb_maple #elif MB(CHITU3D_V5) #include "stm32f1/pins_CHITU3D_V5.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple env:chitu_v5_gpio_init env:chitu_v5_gpio_init_maple #elif MB(CHITU3D_V6) @@ -583,6 +583,8 @@ #include "stm32f1/pins_CREALITY_V24S1.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V24S1_301) #include "stm32f1/pins_CREALITY_V24S1_301.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple +#elif MB(CREALITY_V25S1) + #include "stm32f1/pins_CREALITY_V25S1.h" // STM32F1 env:STM32F103RE_creality_smartPro env:STM32F103RE_creality_smartPro_maple #elif MB(TRIGORILLA_PRO) #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro env:trigorilla_pro_maple #elif MB(FLY_MINI) @@ -676,23 +678,25 @@ #elif MB(MKS_ROBIN_NANO_V3_1) #include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3_1 env:mks_robin_nano_v3_1_usb_flash_drive env:mks_robin_nano_v3_1_usb_flash_drive_msc #elif MB(ANET_ET4) - #include "stm32f4/pins_ANET_ET4.h" // STM32F4 env:Anet_ET4_OpenBLT + #include "stm32f4/pins_ANET_ET4.h" // STM32F4 env:Anet_ET4_no_bootloader env:Anet_ET4_OpenBLT #elif MB(ANET_ET4P) - #include "stm32f4/pins_ANET_ET4P.h" // STM32F4 env:Anet_ET4_OpenBLT + #include "stm32f4/pins_ANET_ET4P.h" // STM32F4 env:Anet_ET4_no_bootloader env:Anet_ET4_OpenBLT #elif MB(FYSETC_CHEETAH_V20) #include "stm32f4/pins_FYSETC_CHEETAH_V20.h" // STM32F4 env:FYSETC_CHEETAH_V20 #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 #elif MB(TH3D_EZBOARD_V2) - #include "stm32f4/pins_TH3D_EZBOARD_V2.h" // STM32F4 env:TH3D_EZBoard_V2 -#elif MB(INDEX_REV03) - #include "stm32f4/pins_INDEX_REV03.h" // STM32F4 env:Index_Mobo_Rev03 + #include "stm32f4/pins_TH3D_EZBOARD_V2.h" // STM32F4 env:TH3D_EZBoard_V2_no_bootloader env:TH3D_EZBoard_V2_OpenBLT +#elif MB(OPULO_LUMEN_REV3) + #include "stm32f4/pins_OPULO_LUMEN_REV3.h" // STM32F4 env:Opulo_Lumen_REV3 #elif MB(MKS_ROBIN_NANO_V1_3_F4) #include "stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h" // STM32F4 env:mks_robin_nano_v1_3_f4 #elif MB(MKS_EAGLE) #include "stm32f4/pins_MKS_EAGLE.h" // STM32F4 env:mks_eagle #elif MB(ARTILLERY_RUBY) #include "stm32f4/pins_ARTILLERY_RUBY.h" // STM32F4 env:Artillery_Ruby +#elif MB(CREALITY_V24S1_301F4) + #include "stm32f4/pins_CREALITY_V24S1_301F4.h" // STM32F4 env:STM32F401RC_creality env:STM32F401RC_creality_jlink env:STM32F401RC_creality_stlink // // ARM Cortex M7 @@ -702,8 +706,14 @@ #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(BTT_SKR_SE_BX_V2) + #include "stm32h7/pins_BTT_SKR_SE_BX_V2.h" // STM32H7 env:BTT_SKR_SE_BX +#elif MB(BTT_SKR_SE_BX_V3) + #include "stm32h7/pins_BTT_SKR_SE_BX_V3.h" // STM32H7 env:BTT_SKR_SE_BX +#elif MB(BTT_SKR_V3_0) + #include "stm32h7/pins_BTT_SKR_V3_0.h" // STM32H7 env:STM32H743Vx_btt +#elif MB(BTT_SKR_V3_0_EZ) + #include "stm32h7/pins_BTT_SKR_V3_0_EZ.h" // STM32H7 env:STM32H743Vx_btt #elif MB(TEENSY41) #include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41 #elif MB(T41U5XBB) @@ -789,6 +799,7 @@ #define BOARD_RAMPS_LONGER3D_LK4PRO 99921 #define BOARD_BTT_SKR_V2_0 99922 #define BOARD_TH3D_EZBOARD_LITE_V2 99923 + #define BOARD_BTT_SKR_SE_BX 99924 #if MB(MKS_13) #error "BOARD_MKS_13 has been renamed BOARD_MKS_GEN_13. Please update your configuration." @@ -837,9 +848,11 @@ #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 MB(BOARD_TH3D_EZBOARD_LITE_V2) + #error "BOARD_BTT_SKR_V2_0 is now BOARD_BTT_SKR_V2_0_REV_A or BOARD_BTT_SKR_V2_0_REV_B. See https://bit.ly/3t5d9JQ for more information. Please update your configuration." + #elif MB(TH3D_EZBOARD_LITE_V2) #error "BOARD_TH3D_EZBOARD_LITE_V2 is now BOARD_TH3D_EZBOARD_V2. Please update your configuration." + #elif MB(BTT_SKR_SE_BX) + #error "BOARD_BTT_SKR_SE_BX is now BOARD_BTT_SKR_SE_BX_V2 or BOARD_BTT_SKR_SE_BX_V3. Please update your configuration." #elif defined(MOTHERBOARD) #error "Unknown MOTHERBOARD value set in Configuration.h." #else @@ -869,6 +882,8 @@ #undef BOARD_RAMPS_DAGOMA #undef BOARD_RAMPS_LONGER3D_LK4PRO #undef BOARD_BTT_SKR_V2_0 + #undef BOARD_TH3D_EZBOARD_LITE_V2 + #undef BOARD_BTT_SKR_SE_BX #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 8da2b969bc02..c3c217557beb 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -486,10 +486,10 @@ #ifndef Z2_USE_ENDSTOP #define Z2_USE_ENDSTOP _ZSTOP_ #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 && !defined(Z3_USE_ENDSTOP) + #if NUM_Z_STEPPERS >= 3 && !defined(Z3_USE_ENDSTOP) #define Z3_USE_ENDSTOP _ZSTOP_ #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 && !defined(Z4_USE_ENDSTOP) + #if NUM_Z_STEPPERS >= 4 && !defined(Z4_USE_ENDSTOP) #define Z4_USE_ENDSTOP _ZSTOP_ #endif #endif @@ -775,14 +775,14 @@ #define X2_MS3_PIN -1 #endif -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !defined(Y2_DIAG_PIN) && !defined(Y2_STEP_PIN) && !PIN_EXISTS(Y2_CS_PIN) +#if HAS_DUAL_Y_STEPPERS && !defined(Y2_DIAG_PIN) && !defined(Y2_STEP_PIN) && !PIN_EXISTS(Y2_CS_PIN) #define Z2_E_INDEX INCREMENT(Y2_E_INDEX) #else #define Z2_E_INDEX Y2_E_INDEX #endif // The Y2 axis, if any, should be the next open extruder port -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) +#if HAS_DUAL_Y_STEPPERS #ifndef Y2_STEP_PIN #define Y2_STEP_PIN _EPIN(Y2_E_INDEX, STEP) #define Y2_DIR_PIN _EPIN(Y2_E_INDEX, DIR) @@ -861,14 +861,14 @@ #define Y2_MS3_PIN -1 #endif -#if NUM_Z_STEPPER_DRIVERS >= 2 && !defined(Z2_DIAG_PIN) && !defined(Z2_STEP_PIN) && !PIN_EXISTS(Z2_CS_PIN) +#if NUM_Z_STEPPERS >= 2 && !defined(Z2_DIAG_PIN) && !defined(Z2_STEP_PIN) && !PIN_EXISTS(Z2_CS_PIN) #define Z3_E_INDEX INCREMENT(Z2_E_INDEX) #else #define Z3_E_INDEX Z2_E_INDEX #endif // The Z2 axis, if any, should be the next open extruder port -#if NUM_Z_STEPPER_DRIVERS >= 2 +#if NUM_Z_STEPPERS >= 2 #ifndef Z2_STEP_PIN #define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP) #define Z2_DIR_PIN _EPIN(Z2_E_INDEX, DIR) @@ -947,14 +947,14 @@ #define Z2_MS3_PIN -1 #endif -#if NUM_Z_STEPPER_DRIVERS >= 3 && !defined(Z3_DIAG_PIN) && !defined(Z3_STEP_PIN) && !PIN_EXISTS(Z3_CS_PIN) +#if NUM_Z_STEPPERS >= 3 && !defined(Z3_DIAG_PIN) && !defined(Z3_STEP_PIN) && !PIN_EXISTS(Z3_CS_PIN) #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) #else #define Z4_E_INDEX Z3_E_INDEX #endif // The Z3 axis, if any, should be the next open extruder port -#if NUM_Z_STEPPER_DRIVERS >= 3 +#if NUM_Z_STEPPERS >= 3 #ifndef Z3_STEP_PIN #define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP) #define Z3_DIR_PIN _EPIN(Z3_E_INDEX, DIR) @@ -1033,14 +1033,14 @@ #define Z3_MS3_PIN -1 #endif -#if NUM_Z_STEPPER_DRIVERS >= 4 && !defined(Z4_DIAG_PIN) && !defined(Z4_STEP_PIN) && !PIN_EXISTS(Z4_CS_PIN) +#if NUM_Z_STEPPERS >= 4 && !defined(Z4_DIAG_PIN) && !defined(Z4_STEP_PIN) && !PIN_EXISTS(Z4_CS_PIN) #define I_E_INDEX INCREMENT(Z4_E_INDEX) #else #define I_E_INDEX Z4_E_INDEX #endif // The Z4 axis, if any, should be the next open extruder port -#if NUM_Z_STEPPER_DRIVERS >= 4 +#if NUM_Z_STEPPERS >= 4 #ifndef Z4_STEP_PIN #define Z4_STEP_PIN _EPIN(Z4_E_INDEX, STEP) #define Z4_DIR_PIN _EPIN(Z4_E_INDEX, DIR) @@ -1664,6 +1664,9 @@ #undef X_MAX_PIN #define X_MAX_PIN -1 #endif +#if NONE(USE_XMIN_PLUG, USE_XMAX_PLUG) + #undef X_STOP_PIN +#endif #if DISABLED(USE_YMIN_PLUG) #undef Y_MIN_PIN #define Y_MIN_PIN -1 @@ -1672,6 +1675,9 @@ #undef Y_MAX_PIN #define Y_MAX_PIN -1 #endif +#if NONE(USE_YMIN_PLUG, USE_YMAX_PLUG) + #undef Y_STOP_PIN +#endif #if DISABLED(USE_ZMIN_PLUG) #undef Z_MIN_PIN #define Z_MIN_PIN -1 @@ -1680,6 +1686,9 @@ #undef Z_MAX_PIN #define Z_MAX_PIN -1 #endif +#if NONE(USE_ZMIN_PLUG, USE_ZMAX_PLUG) + #undef Z_STOP_PIN +#endif #if DISABLED(USE_IMIN_PLUG) #undef I_MIN_PIN #define I_MIN_PIN -1 @@ -1688,6 +1697,9 @@ #undef I_MAX_PIN #define I_MAX_PIN -1 #endif +#if NONE(USE_IMIN_PLUG, USE_IMAX_PLUG) + #undef I_STOP_PIN +#endif #if DISABLED(USE_JMIN_PLUG) #undef J_MIN_PIN #define J_MIN_PIN -1 @@ -1696,6 +1708,9 @@ #undef J_MAX_PIN #define J_MAX_PIN -1 #endif +#if NONE(USE_JMIN_PLUG, USE_JMAX_PLUG) + #undef J_STOP_PIN +#endif #if DISABLED(USE_KMIN_PLUG) #undef K_MIN_PIN #define K_MIN_PIN -1 @@ -1704,6 +1719,9 @@ #undef K_MAX_PIN #define K_MAX_PIN -1 #endif +#if NONE(USE_KMIN_PLUG, USE_KMAX_PLUG) + #undef K_STOP_PIN +#endif #if DISABLED(USE_UMIN_PLUG) #undef U_MIN_PIN #define U_MIN_PIN -1 @@ -1712,6 +1730,9 @@ #undef U_MAX_PIN #define U_MAX_PIN -1 #endif +#if NONE(USE_UMIN_PLUG, USE_UMAX_PLUG) + #undef U_STOP_PIN +#endif #if DISABLED(USE_VMIN_PLUG) #undef V_MIN_PIN #define V_MIN_PIN -1 @@ -1720,6 +1741,9 @@ #undef V_MAX_PIN #define V_MAX_PIN -1 #endif +#if NONE(USE_VMIN_PLUG, USE_VMAX_PLUG) + #undef V_STOP_PIN +#endif #if DISABLED(USE_WMIN_PLUG) #undef W_MIN_PIN #define W_MIN_PIN -1 @@ -1728,6 +1752,9 @@ #undef W_MAX_PIN #define W_MAX_PIN -1 #endif +#if NONE(USE_WMIN_PLUG, USE_WMAX_PLUG) + #undef W_STOP_PIN +#endif #if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MAX #undef X2_MIN_PIN @@ -1747,16 +1774,16 @@ #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 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPERS < 3 || Z_HOME_TO_MAX #undef Z3_MIN_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MIN +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPERS < 3 || Z_HOME_TO_MIN #undef Z3_MAX_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MAX +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPERS < 4 || Z_HOME_TO_MAX #undef Z4_MIN_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MIN +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPERS < 4 || Z_HOME_TO_MIN #undef Z4_MAX_PIN #endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 8bc0a90c0586..413eb8c98cc6 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -84,7 +84,7 @@ #endif #define Z_MAX_PIN 7 -#ifndef Z_MIN_PIN 7 +#ifndef Z_MIN_PIN #define Z_MIN_PIN 10 // Z- #endif diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h index ee8cafa89766..44d8341c11d6 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h @@ -29,7 +29,7 @@ #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." + #error "Azteeg X3 supports up to 2 hotends / E steppers." #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index c2896146e64f..5dc191cd2016 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -29,7 +29,7 @@ #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." + #error "Azteeg X3 Pro supports up to 5 hotends / E steppers." #endif #define BOARD_INFO_NAME "Azteeg X3 Pro" @@ -158,7 +158,7 @@ #if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && defined(DOGLCD_A0) && DOGLCD_A0 == CASE_LIGHT_PIN #undef DOGLCD_A0 // Steal pin 44 for the case light; if you have a Viki2 and have connected it #define DOGLCD_A0 57 // following the Panucatt wiring diagram, you may need to tweak these pin assignments - // as the wiring diagram uses pin 44 for DOGLCD_A0 + // as the wiring diagram uses pin 44 for DOGLCD_A0. #endif // diff --git a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h index 4d7a79263570..fa622ffb15dc 100644 --- a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h +++ b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "2PrintBeta Due supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "2PrintBeta Due supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "2PrintBeta Due" diff --git a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h index b31df115637d..58a62fb8bc74 100644 --- a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h +++ b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "KFB 2.0 supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "KFB 2.0 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "KFB 2.0" diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h index ced66d80b875..e1bd2ec4ed54 100644 --- a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h +++ b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h @@ -22,7 +22,7 @@ #pragma once #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Dagoma3D F5 supports only 2 hotends / E-steppers. Comment out this line to continue." + #error "Dagoma3D F5 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Dagoma3D F5" diff --git a/Marlin/src/pins/ramps/pins_FELIX2.h b/Marlin/src/pins/ramps/pins_FELIX2.h index bdf83c44ba8e..3e7849d71f23 100644 --- a/Marlin/src/pins/ramps/pins_FELIX2.h +++ b/Marlin/src/pins/ramps/pins_FELIX2.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Felix 2.0+ supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "Felix 2.0+ supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Felix 2.0+" diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index 845e2d65ec0f..a6791ff7c8b5 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -29,7 +29,7 @@ #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." + #error "Formbot supports up to 3 hotends / E steppers." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 7a128318620b..17d3abc71f37 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -29,7 +29,7 @@ #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." + #error "Formbot supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Formbot" diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 0a94a582d43c..e23a63994faa 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -29,7 +29,7 @@ #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." + #error "Formbot supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Formbot" diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 9c6b74f1269d..b8de260909b6 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -234,7 +234,7 @@ #if ENABLED(FYSETC_MINI_12864) // - // See https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 + // See https://wiki.fysetc.com/Mini12864_Panel/ // #define DOGLCD_A0 16 #define DOGLCD_CS 17 diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index 2dabd9d59b93..a9613e8eb27f 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -26,7 +26,7 @@ */ #if HAS_MULTI_HOTEND - #error "Only 1 hotend is supported for Vertex Nano." + #error "K8600 only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "K8600" diff --git a/Marlin/src/pins/ramps/pins_K8800.h b/Marlin/src/pins/ramps/pins_K8800.h index f1362ec61d34..17bb59fdc9d0 100644 --- a/Marlin/src/pins/ramps/pins_K8800.h +++ b/Marlin/src/pins/ramps/pins_K8800.h @@ -105,9 +105,6 @@ #define LCD_PINS_D6 33 #define LCD_PINS_D7 31 - #define LCD_CONTRAST_MIN 0 - #define LCD_CONTRAST_MAX 100 - #define LCD_CONTRAST_INIT 30 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #if IS_NEWPANEL diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index a7817c6f3a7b..af1d33c83c60 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -29,7 +29,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Longer3D LGT KIT V1.0 board only supports one hotend / E-stepper. Comment out this line to continue." + #error "Longer3D LGT KIT V1.0 only supports 1 hotend / E stepper." #endif #if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || SERIAL_PORT_3 == 1 diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_10.h b/Marlin/src/pins/ramps/pins_MKS_BASE_10.h index c40cabe32515..64efa46c0550 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_10.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_10.h @@ -28,7 +28,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS BASE 1.0 supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS BASE 1.0 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS BASE 1.0" diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h index 992ab92ee9c2..7e2a722cf222 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS BASE 1.4 only supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS BASE 1.4 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS BASE 1.4" diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_15.h b/Marlin/src/pins/ramps/pins_MKS_BASE_15.h index 2b0c2bb88300..5fedd3f97c8a 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_15.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_15.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS BASE 1.5 only supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS BASE 1.5 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS BASE 1.5" diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h index 31a8fdab8d3a..63e0b51d3cc5 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS BASE 1.6 only supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS BASE 1.6 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS BASE 1.6" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index 5f373f99d74b..bb7b55893ec1 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -31,7 +31,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS GEN 1.3/1.4 supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS GEN 1.3/1.4 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS GEN >= v1.3" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h index 4dca1ca187b0..ca1f1338164e 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS GEN L supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS GEN L supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS GEN L" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h index 20f3dece4273..0378b166a2d4 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS GEN L V2 supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS GEN L V2 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS GEN L V2" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h index 24e04a39ff1f..d508cb453f4d 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS GEN L V2.1 supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS GEN L V2.1 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS GEN L V2.1" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index c7ef0be99e64..d779372b1b84 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -78,6 +78,31 @@ #define SERVO3_PIN 4 #endif +// +// Foam Cutter requirements +// + +#if ENABLED(FOAMCUTTER_XYUV) + #ifndef MOSFET_C_PIN + #define MOSFET_C_PIN -1 + #endif + #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) && NUM_SERVOS < 2 + #define SPINDLE_LASER_PWM_PIN 8 // Hardware PWM + #endif + #ifndef Z_MIN_PIN + #define Z_MIN_PIN -1 + #endif + #ifndef Z_MAX_PIN + #define Z_MAX_PIN -1 + #endif + #ifndef I_STOP_PIN + #define I_STOP_PIN 18 + #endif + #ifndef J_STOP_PIN + #define J_STOP_PIN 19 + #endif +#endif + // // Limit Switches // @@ -272,7 +297,9 @@ #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS < 2 // Use servo connector if possible #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #ifndef SPINDLE_LASER_PWM_PIN + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #endif #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! @@ -592,7 +619,10 @@ #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ZONESTAR_LCD on RAMPS requires wiring modifications. It plugs into AUX2 but GND and 5V need to be swapped. See 'pins_RAMPS.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif + #define LCD_PINS_RS AUX2_05_PIN #define LCD_PINS_ENABLE AUX2_07_PIN #define LCD_PINS_D4 AUX2_04_PIN @@ -600,6 +630,10 @@ #define LCD_PINS_D6 AUX2_08_PIN #define LCD_PINS_D7 AUX2_10_PIN + #elif ENABLED(AZSMZ_12864) + + // Pins only defined for RAMPS_SMART currently + #else #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) @@ -752,7 +786,7 @@ #elif ENABLED(FYSETC_MINI_12864) - // From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 + // From https://wiki.fysetc.com/Mini12864_Panel/ #define DOGLCD_A0 EXP1_07_PIN #define DOGLCD_CS EXP1_08_PIN @@ -855,7 +889,9 @@ #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) - #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_RAMPS.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_RAMPS.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * FYSETC TFT-81050 display pinout diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index 679503e98268..3d5f5d6f9107 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -22,7 +22,7 @@ #pragma once #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Creality3D RAMPS supports only 2 hotends / E-steppers. Comment out this line to continue." + #error "Creality RAMPS supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Creality3D RAMPS" diff --git a/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h b/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h index 358395890624..8f9148b732ee 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 HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Ender-4 only supports one hotend / E-stepper. Comment out this line to continue." + #error "Ender-4 only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "Ender-4" diff --git a/Marlin/src/pins/ramps/pins_RL200.h b/Marlin/src/pins/ramps/pins_RL200.h index 047ad160bed1..00fb39a43901 100644 --- a/Marlin/src/pins/ramps/pins_RL200.h +++ b/Marlin/src/pins/ramps/pins_RL200.h @@ -30,9 +30,9 @@ #define DEFAULT_MACHINE_NAME "Rapide Lite 200" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "RL200v1 supports up to 2 hotends / E-steppers. Comment out this line to continue." -#elif NUM_Z_STEPPER_DRIVERS != 2 - #error "RL200 uses dual Z stepper motors. Set NUM_Z_STEPPER_DRIVERS to 2 or comment out this line to continue." + #error "RL200v1 supports up to 2 hotends / E steppers." +#elif NUM_Z_STEPPERS != 2 + #error "RL200 uses dual Z stepper motors. Z_DRIVER_TYPE and Z2_DRIVER_TYPE must be defined." #elif !(AXIS_DRIVER_TYPE_X(DRV8825) && AXIS_DRIVER_TYPE_Y(DRV8825) && AXIS_DRIVER_TYPE_Z(DRV8825) && AXIS_DRIVER_TYPE_Z2(DRV8825) && AXIS_DRIVER_TYPE_E0(DRV8825)) #error "You must set ([XYZ]|Z2|E0)_DRIVER_TYPE to DRV8825 in Configuration.h for RL200." #endif diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index 7d17bf2e12ed..eb049c48dd99 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -29,7 +29,7 @@ #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." + #error "RUMBA supports up to 3 hotends / E steppers." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h b/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h index 85defdf1bd80..d25029a7a39c 100644 --- a/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h +++ b/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Sainsmart 2-in-1 supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "Sainsmart 2-in-1 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Sainsmart" diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index b884fcbfc7c1..b11487b21d36 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -29,7 +29,7 @@ #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." + #error "Tenlog supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Tenlog D3 Hero" @@ -148,6 +148,7 @@ // // Misc. Functions // +//#define PS_ON_PIN 40 // The M80/M81 PSU pin for boards v2.1-2.3 //#define CASE_LIGHT_PIN 5 #define SDSS 53 //#ifndef LED_PIN 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 ffe6d56eb8b1..04c6af67b002 100644 --- a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h +++ b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h @@ -29,7 +29,7 @@ #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." + #error "TRONXY-V3-1.0 supports up to 2 hotends/E steppers." #endif #define BOARD_INFO_NAME "TRONXY-V3-1.0" diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 9d844ebcdcba..f81cc6039aed 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -24,7 +24,7 @@ #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." + #error "TTOSCAR supports up to 5 hotends / E steppers." #endif #define BOARD_INFO_NAME "TT OSCAR" diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V52.h b/Marlin/src/pins/ramps/pins_ZRIB_V52.h index 002b9dbef580..2df789cd6f7f 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V52.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V52.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "ZRIB V5.2 only supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "ZRIB V5.2 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "ZRIB V5.2" diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 6cbc0351ba98..48808d9601c8 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -28,9 +28,9 @@ #include "env_validate.h" #if HOTENDS > 2 - #error "ZRIB V5.3 only supports up to 2 hotends. Comment out this line to continue." + #error "ZRIB V5.3 supports up to 2 hotends." #elif E_STEPPERS > 3 - #error "ZRIB V5.3 only supports up to 3 E-steppers. Comment out this line to continue." + #error "ZRIB V5.3 supports up to 3 E steppers." #endif #define BOARD_INFO_NAME "ZRIB V5.3" @@ -118,7 +118,7 @@ #define Z_DIR_PIN 48 #define Z_ENABLE_PIN 62 -#if NUM_Z_STEPPER_DRIVERS == 2 +#if NUM_Z_STEPPERS == 2 #define Z2_STEP_PIN 26 // E0 connector #define Z2_DIR_PIN 28 #define Z2_ENABLE_PIN 24 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 feaa4ba98b95..b68e3edb4567 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -29,7 +29,7 @@ #include "env_validate.h" #if HOTENDS > 4 || E_STEPPERS > 4 - #error "Z-Bolt X Series board supports up to 4 hotends / E-steppers." + #error "Z-Bolt X Series supports up to 4 hotends / E steppers." #endif #define BOARD_INFO_NAME "Z-Bolt X Series" diff --git a/Marlin/src/pins/sam/pins_KRATOS32.h b/Marlin/src/pins/sam/pins_KRATOS32.h index f429e5634706..f7867f9b2607 100644 --- a/Marlin/src/pins/sam/pins_KRATOS32.h +++ b/Marlin/src/pins/sam/pins_KRATOS32.h @@ -34,7 +34,7 @@ // #if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x1F400 // 16KB + #define MARLIN_EEPROM_SIZE 0x1F400 // 16K #endif // diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index da176f444784..af24014614c1 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -34,7 +34,7 @@ // #if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x2000 // 8KB + #define MARLIN_EEPROM_SIZE 0x2000 // 8K #endif // diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index 30f209ad3713..980a957a505a 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -134,71 +134,98 @@ #define SDSS 4 #define LED_PIN 13 +/** ------ ------ + * 37 |10 9 | 35 (MISO) 50 |10 9 | 76 (SCK) + * 29 | 8 7 | 27 (EN2) 31 | 8 7 | 4 (SD_SS) + * 25 6 5 | 23 (EN1) 33 6 5 | 75 (MOSI) + * 16 | 4 3 | 17 (SDD) 49 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN 17 +#define EXP1_04_PIN 16 +#define EXP1_05_PIN 23 +#define EXP1_06_PIN 25 +#define EXP1_07_PIN 27 +#define EXP1_08_PIN 29 +#define EXP1_09_PIN 35 +#define EXP1_10_PIN 37 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN 49 +#define EXP2_05_PIN 75 +#define EXP2_06_PIN 33 +#define EXP2_07_PIN 4 +#define EXP2_08_PIN 31 +#define EXP2_09_PIN 76 +#define EXP2_10_PIN 74 + // // LCD / Controller // #if HAS_WIRED_LCD // ramps-fd lcd adaptor - #define BEEPER_PIN 37 - #define BTN_EN1 33 - #define BTN_EN2 31 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_EN1 EXP2_06_PIN + #define BTN_EN2 EXP2_08_PIN + #define BTN_ENC EXP1_09_PIN + #define SD_DETECT_PIN EXP2_04_PIN #if IS_NEWPANEL - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN #endif #if ENABLED(FYSETC_MINI_12864) #define DOGLCD_CS LCD_PINS_ENABLE #define DOGLCD_A0 LCD_PINS_RS - #define DOGLCD_SCK 76 - #define DOGLCD_MOSI 75 + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 25 + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 27 + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 29 + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN EXP1_06_PIN #endif #elif IS_NEWPANEL - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(MINIPANEL) - #define DOGLCD_CS 25 - #define DOGLCD_A0 27 + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN #endif #endif #if ANY(VIKI2, miniVIKI) - #define DOGLCD_A0 16 + #define DOGLCD_A0 EXP1_04_PIN #define KILL_PIN 51 - #define STAT_LED_BLUE_PIN 29 - #define STAT_LED_RED_PIN 23 - #define DOGLCD_CS 17 - #define DOGLCD_SCK 76 // SCK_PIN - Required for DUE Hardware SPI - #define DOGLCD_MOSI 75 // MOSI_PIN - #define DOGLCD_MISO 74 // MISO_PIN + #define STAT_LED_BLUE_PIN EXP1_08_PIN + #define STAT_LED_RED_PIN EXP1_05_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_SCK EXP2_09_PIN // SCK_PIN - Required for DUE Hardware SPI + #define DOGLCD_MOSI EXP2_05_PIN // MOSI_PIN + #define DOGLCD_MISO EXP2_10_PIN // MISO_PIN #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index 96d0c9e1cc9a..2b8942c6ad2d 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -61,53 +61,43 @@ */ #define BOARD_INFO_NAME "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 +#define MARLIN_EEPROM_SIZE 0x1000 // 4K // 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 +#define EEPROM_DEVICE_ADDRESS 0x50 // 7 bit i2c address (without R/W bit) +#define EEPROM_WRITE_DELAY 7 // page write time in milliseconds (docs say 5ms but that is too short) +//#define EEPROM_PAGE_SIZE 64 // page write buffer size +//#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 // // Temperature Sensors // -#undef TEMP_0_PIN #define TEMP_0_PIN 9 // Analog Input - -#undef TEMP_1_PIN #define TEMP_1_PIN 10 // Analog Input - -#undef TEMP_BED_PIN #define TEMP_BED_PIN 11 // Analog Input // SPI for MAX Thermocouple -#undef TEMP_0_CS_PIN #if DISABLED(SDSUPPORT) #define TEMP_0_CS_PIN 67 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 67 // Don't use 49 (SD_DETECT_PIN) #endif +#define SDA_PIN 20 +#define SCL_PIN 21 +#define RESET_PIN 42 // Resets the board if the jumper is attached + // // LCD / Controller // - -// Support for AZSMZ 12864 LCD with SD Card 3D printer smart controller control panel #if ENABLED(AZSMZ_12864) + + // Support for AZSMZ 12864 LCD with SD Card 3D printer smart controller control panel #define BEEPER_PIN 66 // Smart RAMPS 1.42 pinout diagram on RepRap WIKI erroneously says this should be pin 65 #define DOGLCD_A0 59 #define DOGLCD_CS 44 @@ -116,4 +106,37 @@ #define BTN_ENC 67 // Smart RAMPS 1.42 pinout diagram on RepRap WIKI erroneously says this should be pin 66 #define SD_DETECT_PIN 49 // Pin 49 for display sd interface, 72 for easy adapter board #define KILL_PIN 42 + +#else + + /** ------ ------ + * 37 |10 9 | 35 (MISO) 50 |10 9 | 52 (SCK) + * 31 | 8 7 | 41 29 | 8 7 | 53 + * 33 6 5 | 23 25 6 5 | 51 (MOSI) + * 42 | 4 3 | 44 49 | 4 3 | 27 + * GND | 2 1 | 5V GND | 2 1 | -- + * ------ ------ + * EXP1 EXP2 + */ + #define EXP1_03_PIN 44 + #define EXP1_04_PIN 42 + #define EXP1_05_PIN 23 + #define EXP1_06_PIN 33 + #define EXP1_07_PIN 41 + #define EXP1_08_PIN 31 + #define EXP1_09_PIN 35 + #define EXP1_10_PIN 37 + + #define EXP2_03_PIN 27 + #define EXP2_04_PIN 49 + #define EXP2_05_PIN 51 + #define EXP2_06_PIN 25 + #define EXP2_07_PIN 53 + #define EXP2_08_PIN 29 + #define EXP2_09_PIN 52 + #define EXP2_10_PIN 50 + #endif + +#define ALLOW_SAM3X8E +#include "../ramps/pins_RAMPS.h" diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 4bdadd80828e..064ce2751ab3 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -18,19 +18,12 @@ * You should have received a copy of the GNU General Public License * along with this program. If not, see . * - * Ported sys0724 & Vynt */ #pragma once /** * Arduino Mega? or Due with RuRAMPS4DUE pin assignments - * - * Applies to the following boards: - * RURAMPS4DUE (Hotend0, Hotend1, Hotend2, Fan0, Fan1, Bed) - * - * Differences between - * RADDS | RuRAMPS4DUE - * | + * Ported by sys0724 & Vynt */ #include "env_validate.h" @@ -153,7 +146,7 @@ // SPI for MAX Thermocouple /* #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN 53 + #define TEMP_0_CS_PIN EXP1_03_PIN #else #define TEMP_0_CS_PIN 49 #endif @@ -179,7 +172,7 @@ // // EEPROM // -#define MARLIN_EEPROM_SIZE 0x8000 // 32Kb (24lc256) +#define MARLIN_EEPROM_SIZE 0x8000 // 32K (24lc256) #define I2C_EEPROM // EEPROM on I2C-0 //#define EEPROM_SD // EEPROM on SDCARD //#define SPI_EEPROM // EEPROM on SPI-0 @@ -190,59 +183,87 @@ // 32Mb FLASH //#define SPI_FLASH_CS_PIN ? +/** + * ------ ------ + * (BEEPER) 62 |10 9 | 40 (BTN_ENC) (MISO) 74 |10 9 | 76 (SCK) + * (LCD_EN) 64 | 8 7 | 63 (LCD_RS) (BTN_EN1) 44 | 8 7 | 10 (SD_SS) + * (LCD_D4) 48 | 6 5 50 (LCD_D5) (BTN_EN2) 42 | 6 5 75 (MOSI) + * (LCD_D6) 52 | 4 3 | 53 (LCD_D7) (SD_DETECT) 51 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN 53 +#define EXP1_04_PIN 52 +#define EXP1_05_PIN 50 +#define EXP1_06_PIN 48 +#define EXP1_07_PIN 63 +#define EXP1_08_PIN 64 +#define EXP1_09_PIN 40 +#define EXP1_10_PIN 62 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN 51 +#define EXP2_05_PIN 75 // MOSI +#define EXP2_06_PIN 42 +#define EXP2_07_PIN 10 +#define EXP2_08_PIN 44 +#define EXP2_09_PIN 76 // SCK +#define EXP2_10_PIN 74 // MISO + // // LCD / Controller // #if HAS_WIRED_LCD #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 - #define LCD_PINS_D6 52 - #define LCD_PINS_D7 53 - #define SD_DETECT_PIN 51 + #define BEEPER_PIN EXP1_10_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + #define SD_DETECT_PIN EXP2_04_PIN #endif #if EITHER(RADDS_DISPLAY, IS_RRD_SC) - #define LCD_PINS_RS 63 - #define LCD_PINS_ENABLE 64 + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN #elif IS_RRD_FG_SC - #define LCD_PINS_RS 52 - #define LCD_PINS_ENABLE 53 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN #elif HAS_U8GLIB_I2C_OLED - #define BEEPER_PIN 62 - #define LCD_SDSS 10 - #define SD_DETECT_PIN 51 + #define BEEPER_PIN EXP1_10_PIN + #define LCD_SDSS EXP2_07_PIN + #define SD_DETECT_PIN EXP2_04_PIN #elif ENABLED(FYSETC_MINI_12864) - #define BEEPER_PIN 62 - #define DOGLCD_CS 64 - #define DOGLCD_A0 63 + #define BEEPER_PIN EXP1_10_PIN + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_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 48 // 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 50 // D5 + #define RGB_LED_R_PIN EXP1_05_PIN // D5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 52 // D6 + #define RGB_LED_G_PIN EXP1_04_PIN // D6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 53 // D7 + #define RGB_LED_B_PIN EXP1_03_PIN // D7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 50 // D5 + #define NEOPIXEL_PIN EXP1_05_PIN // D5 #endif #elif ENABLED(SPARK_FULL_GRAPHICS) @@ -259,9 +280,9 @@ #endif // SPARK_FULL_GRAPHICS #if IS_NEWPANEL - #define BTN_EN1 44 - #define BTN_EN2 42 - #define BTN_ENC 40 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 5273cbcd0e93..cc919d0a4fdc 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -162,7 +162,7 @@ // // EEPROM // -#define MARLIN_EEPROM_SIZE 0x8000 // 32Kb (24lc256) +#define MARLIN_EEPROM_SIZE 0x8000 // 32K (24lc256) #define I2C_EEPROM // EEPROM on I2C-0 //#define EEPROM_SD // EEPROM on SDCARD //#define SPI_EEPROM // EEPROM on SPI-0 @@ -173,74 +173,101 @@ // 32Mb FLASH //#define SPI_FLASH_CS_PIN ? +/** + * ------ ------ + * (BEEPER) 62 |10 9 | 40 (BTN_ENC) (MISO) 74 |10 9 | 76 (SCK) + * (LCD_EN) 64 | 8 7 | 63 (LCD_RS) (BTN_EN1) 44 | 8 7 | 10 (SD_SS) + * (LCD_D4) 48 | 6 5 50 (LCD_D5) (BTN_EN2) 42 | 6 5 75 (MOSI) + * (LCD_D6) 52 | 4 3 | 53 (LCD_D7) (SD_DETECT) 51 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN 53 +#define EXP1_04_PIN 52 +#define EXP1_05_PIN 50 +#define EXP1_06_PIN 48 +#define EXP1_07_PIN 63 +#define EXP1_08_PIN 64 +#define EXP1_09_PIN 40 +#define EXP1_10_PIN 62 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN 51 +#define EXP2_05_PIN 75 // MOSI +#define EXP2_06_PIN 42 +#define EXP2_07_PIN 10 +#define EXP2_08_PIN 44 +#define EXP2_09_PIN 76 // SCK +#define EXP2_10_PIN 74 // MISO + // // LCD / Controller // #if HAS_WIRED_LCD #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 - #define LCD_PINS_D6 52 - #define LCD_PINS_D7 53 - #define SD_DETECT_PIN 51 + #define BEEPER_PIN EXP1_10_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + #define SD_DETECT_PIN EXP2_04_PIN #endif #if EITHER(RADDS_DISPLAY, IS_RRD_SC) - #define LCD_PINS_RS 63 - #define LCD_PINS_ENABLE 64 + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN #elif IS_RRD_FG_SC - #define LCD_PINS_RS 52 - #define LCD_PINS_ENABLE 53 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN #elif HAS_U8GLIB_I2C_OLED - #define BEEPER_PIN 62 - #define LCD_SDSS 10 - #define SD_DETECT_PIN 51 + #define BEEPER_PIN EXP1_10_PIN + #define LCD_SDSS EXP2_07_PIN + #define SD_DETECT_PIN EXP2_04_PIN #elif ENABLED(FYSETC_MINI_12864) - #define BEEPER_PIN 62 - #define DOGLCD_CS 64 - #define DOGLCD_A0 63 + #define BEEPER_PIN EXP1_10_PIN + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_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 48 // 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 50 // D5 + #define RGB_LED_R_PIN EXP1_05_PIN // D5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 52 // D6 + #define RGB_LED_G_PIN EXP1_04_PIN // D6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 53 // D7 + #define RGB_LED_B_PIN EXP1_03_PIN // D7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 50 // D5 + #define NEOPIXEL_PIN EXP1_05_PIN // D5 #endif #elif ENABLED(MKS_MINI_12864) + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_A0 52 - #define DOGLCD_CS 50 - - #define SD_DETECT_PIN 51 + #define SD_DETECT_PIN EXP2_04_PIN #endif #if IS_NEWPANEL - #define BTN_EN1 44 - #define BTN_EN2 42 - #define BTN_ENC 40 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h index 1e0efcf0b21d..382c607d239b 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h @@ -44,7 +44,7 @@ */ //#define FLASH_EEPROM_EMULATION #define I2C_EEPROM // EEPROM on I2C-0 -#define MARLIN_EEPROM_SIZE 0x70000 // 512K (CAT24C512) +#define MARLIN_EEPROM_SIZE 0x10000 // 64K (CAT24C512) // This is another option to emulate an EEPROM, but it's more efficient to not lose the data in the first place. //#define SDCARD_EEPROM_EMULATION @@ -439,7 +439,7 @@ #elif ENABLED(FYSETC_MINI_12864) - // From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 + // From https://wiki.fysetc.com/Mini12864_Panel/ // TO TEST //#define DOGLCD_A0 16 diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h index 2484674a90b3..0f4bb1d0b591 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h @@ -48,7 +48,7 @@ */ //#define FLASH_EEPROM_EMULATION #define I2C_EEPROM // EEPROM on I2C-0 -#define MARLIN_EEPROM_SIZE 0x70000 // 512K (CAT24C512) +#define MARLIN_EEPROM_SIZE 0x10000 // 64K (CAT24C512) //This its another option to emulate an EEPROM, but its more efficient to dont loose the data the first One. //#define SDCARD_EEPROM_EMULATION @@ -110,7 +110,7 @@ // This board have the option to use an extra TMC2209 stepper, one of the use could be as a second extruder. #if EXTRUDERS < 2 // TODO: Corregir aquí que cuando tenemos dos extrusores o lo que sea, utiliza los endstop que le sobran, osea los max, no hay Z2_endstop - #if NUM_Z_STEPPER_DRIVERS > 1 + #if NUM_Z_STEPPERS > 1 #define Z2_STOP_PIN 14 #endif #else @@ -490,7 +490,7 @@ #elif ENABLED(FYSETC_MINI_12864) - // From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 + // From https://wiki.fysetc.com/Mini12864_Panel/ // TO TEST //#define DOGLCD_A0 16 diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index db6cb2353b3f..061e27faf4f7 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -778,7 +778,7 @@ #define _X2_PINS #endif -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) +#if HAS_DUAL_Y_STEPPERS #if PIN_EXISTS(Y2_CS) && AXIS_HAS_SPI(Y2) #define _Y2_CS Y2_CS_PIN, #else @@ -804,7 +804,7 @@ #define _Y2_PINS #endif -#if NUM_Z_STEPPER_DRIVERS >= 2 +#if NUM_Z_STEPPERS >= 2 #if PIN_EXISTS(Z2_CS) && AXIS_HAS_SPI(Z2) #define _Z2_CS Z2_CS_PIN, #else @@ -830,7 +830,7 @@ #define _Z2_PINS #endif -#if NUM_Z_STEPPER_DRIVERS >= 3 +#if NUM_Z_STEPPERS >= 3 #if PIN_EXISTS(Z3_CS) && AXIS_HAS_SPI(Z3) #define _Z3_CS Z3_CS_PIN, #else @@ -856,7 +856,7 @@ #define _Z3_PINS #endif -#if NUM_Z_STEPPER_DRIVERS >= 4 +#if NUM_Z_STEPPERS >= 4 #if PIN_EXISTS(Z4_CS) && AXIS_HAS_SPI(Z4) #define _Z4_CS Z4_CS_PIN, #else diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h index 904a9a56fac6..d38d4bbdb378 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -33,7 +33,7 @@ #if NO_EEPROM_SELECTED #define FLASH_EEPROM_EMULATION #ifndef MARLIN_EEPROM_SIZE - #define MARLIN_EEPROM_SIZE 0x800U // 2KB + #define MARLIN_EEPROM_SIZE 0x800U // 2K #endif #endif diff --git a/Marlin/src/pins/stm32f1/env_validate.h b/Marlin/src/pins/stm32f1/env_validate.h index 2e7b78517215..2d325428ac8c 100644 --- a/Marlin/src/pins/stm32f1/env_validate.h +++ b/Marlin/src/pins/stm32f1/env_validate.h @@ -22,5 +22,11 @@ #pragma once #if NOT_TARGET(__STM32F1__, STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" + #if DISABLED(ALLOW_STM32F4) + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" + #elif NOT_TARGET(STM32F4) + #error "Oops! Select an STM32F4 board in 'Tools > Board.'" + #endif #endif + +#undef ALLOW_STM32F4 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index 7b8abb130060..e3e91ff35ad4 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -52,9 +52,9 @@ #if ENABLED(I2C_EEPROM) #define IIC_EEPROM_SDA PB7 #define IIC_EEPROM_SCL PB6 - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #elif ENABLED(SDCARD_EEPROM_EMULATION) - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #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 704501de108b..06788139f01f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -33,9 +33,9 @@ #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif // @@ -182,7 +182,9 @@ #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_DIP.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif #define LCD_PINS_RS PB9 #define LCD_PINS_ENABLE PB6 @@ -224,7 +226,9 @@ #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) - #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_E3_DIP.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_E3_DIP.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** FYSETC TFT TFT81050 display pinout * 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 2ab7a61e0b95..b5fddc4d7494 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 @@ -29,7 +29,7 @@ #if NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #define I2C_SDA_PIN PB7 #define I2C_SCL_PIN PB6 #undef NO_EEPROM_SELECTED 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 5b48d7cadbcf..fa7eb3dd115c 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 @@ -33,9 +33,9 @@ #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif // @@ -150,7 +150,9 @@ * All pins are labeled as printed on DWIN PCB. Connect TX-TX, A-A and so on. */ - #error "Ender-3 V2 display requires a custom cable, see diagram above this line. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! Ender-3 V2 display requires a custom cable. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif #define BEEPER_PIN EXP1_9 #define BTN_EN1 EXP1_3 @@ -173,7 +175,9 @@ #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif #define LCD_PINS_RS PB9 #define LCD_PINS_ENABLE EXP1_9 @@ -201,7 +205,9 @@ #if ENABLED(TFTGLCD_PANEL_SPI) - #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * TFTGLCD_PANEL_SPI display pinout @@ -238,7 +244,9 @@ #elif ENABLED(FYSETC_MINI_12864_2_1) - #error "CAUTION! FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864_V1 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864_V1 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864_V1 display pinout @@ -308,7 +316,9 @@ #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) - #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * FYSETC TFT TFT81050 display pinout 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 4f52dfb4fc8c..1ea947ffdf18 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 @@ -33,9 +33,9 @@ #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index b0b201f1d50d..9dec1e127967 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -24,7 +24,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "CCROBOT-ONLINE MEEB_3DP only supports one hotend / E-stepper. Comment out this line to continue." + #error "CCROBOT-ONLINE MEEB_3DP only supports 1 hotend / E stepper." #endif // https://github.com/ccrobot-online/MEEB_3DP @@ -43,9 +43,9 @@ // #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE 0x800U // 2KB + #define EEPROM_PAGE_SIZE 0x800U // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h index 989b7eec6f65..bc41e97041fc 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h @@ -44,10 +44,10 @@ #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 EEPROM_PAGE_SIZE (0x800U) // 2K, but will use 2x more (4K) #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE #else - #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM + #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2K, require this amount of RAM #endif // diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1.h index 9d7e0f695b79..0d2ad835d397 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1.h @@ -22,7 +22,7 @@ #pragma once /** - * Creality v2.4.S1 (STM32F103RE / STM32F103RC) v101 as found in the Ender 7 board pin assignments + * Creality v2.4.S1 (STM32F103RE / STM32F103RC) v101 as found in the Ender 7 */ #define BOARD_INFO_NAME "Creality v2.4.S1 V101" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h index fb7198e57c21..53953f9ebccc 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h @@ -22,21 +22,26 @@ #pragma once /** - * Creality V24S1_301 (STM32F103RE / STM32F103RC) board pin assignments as found on Ender 3 S1 + * Creality V24S1_301 (STM32F103RE / STM32F103RC) board pin assignments as found on Ender 3 S1. + * Also supports the STM32F4 version of the board with identical pin mapping. */ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Creality V24S1 only supports one hotend / E-stepper. Comment out this line to continue." + #error "Creality v24S1 only supports 1 hotend / E stepper." #endif #if BOTH(BLTOUCH, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #error "Disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN when using BLTOUCH with Creality V24S1-301." #endif -#define BOARD_INFO_NAME "Creality V24S1-301" -#define DEFAULT_MACHINE_NAME "Ender 3 S1" +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Creality V24S1-301" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "Ender 3 S1" +#endif // // Servos @@ -70,8 +75,8 @@ // // SD Card // -#define ONBOARD_SPI_DEVICE 1 -#define ONBOARD_SD_CS_PIN PA4 // SDSS +#define ONBOARD_SPI_DEVICE 1 +#define ONBOARD_SD_CS_PIN PA4 // SDSS // // M3/M4/M5 - Spindle/Laser Control @@ -80,9 +85,10 @@ //#define HEATER_0_PIN -1 //#define HEATER_BED_PIN -1 #define FAN_PIN -1 - #define SPINDLE_LASER_ENA_PIN PA0 // FET 1 - #define SPINDLE_LASER_PWM_PIN PA0 // Bed FET - #define SPINDLE_DIR_PIN PA0 // FET 4 + #define SPINDLE_LASER_ENA_PIN PC0 // FET 1 + #define SPINDLE_LASER_PWM_PIN PC0 // Bed FET + #define SPINDLE_DIR_PIN PC0 // FET 4 + #define LASER_SOFT_PWM_PIN PC0 #endif #include "pins_CREALITY_V4.h" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h new file mode 100644 index 000000000000..a0152a522166 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h @@ -0,0 +1,152 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 v2.5.S1 (STM32F103RE / STM32F103RC) as found in the CR-10 Smart Pro + */ + +#include "env_validate.h" + +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 + #error "Creality V2.5.S1 only supports 1 hotend / E stepper." +#endif + +#define BOARD_INFO_NAME "Creality v2.5.S1" +#define DEFAULT_MACHINE_NAME "Creality3D" + +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// +#define DISABLE_DEBUG + +// +// EEPROM +// +#if NO_EEPROM_SELECTED + #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 + //#define SDCARD_EEPROM_EMULATION + //#define FLASH_EEPROM_EMULATION +#endif + +#if ENABLED(IIC_BL24CXX_EEPROM) + #define IIC_EEPROM_SDA PA11 + #define IIC_EEPROM_SCL PA12 + #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) +#elif EITHER(SDCARD_EEPROM_EMULATION, FLASH_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x800 // 2K +#endif + +// +// Limit Switches +// +#define X_STOP_PIN PC4 +#define Y_STOP_PIN PC5 + +#if ENABLED(BLTOUCH) + #define Z_STOP_PIN -1 + #define SERVO0_PIN PC14 // BLTouch OUT PIN + #ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PC15 // BLTouch IN PIN + #endif +#else + #define Z_STOP_PIN PC15 + #if ENABLED(PROBE_ACTIVATION_SWITCH) + #define PROBE_TARE_PIN PC14 + #define PROBE_ACTIVATION_SWITCH_PIN PB2 + #endif +#endif + +// +// Filament Runout Sensor +// +#if ENABLED(FILAMENT_RUNOUT_SENSOR) + #define FIL_RUNOUT_PIN PA15 // "Pulled-high" +#endif + +// +// Steppers +// +#define X_STEP_PIN PB8 +#define X_DIR_PIN PB7 +#define X_ENABLE_PIN PC3 + +#define Y_STEP_PIN PB6 +#define Y_DIR_PIN PB5 +#define Y_ENABLE_PIN X_ENABLE_PIN + +#define Z_STEP_PIN PB4 +#define Z_DIR_PIN PB3 +#define Z_ENABLE_PIN X_ENABLE_PIN + +#define E0_STEP_PIN PC2 +#define E0_DIR_PIN PB9 +#define E0_ENABLE_PIN X_ENABLE_PIN + +// +// Temperature Sensors +// +#define TEMP_0_PIN PB1 // TH1 +#define TEMP_BED_PIN PB0 // TB1 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PB14 // HEATER1 +#define HEATER_BED_PIN PB13 // HOT BED + +#define FAN_PIN PB15 // FAN +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN PC13 // FAN +#endif +#define FAN_SOFT_PWM_REQUIRED + +// +// SD Card +// +#define SD_DETECT_PIN PC7 +#define SDCARD_CONNECTION ONBOARD +#define ON_BOARD_SPI_DEVICE 1 +#define ONBOARD_SD_CS_PIN PC12 // SDSS +#define SDIO_SUPPORT +#define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer + +// +// Misc. Functions +// +#define CASE_LIGHT_PIN PA7 + +// +// Suicide Power +// +#define PS_ON_PIN PA0 +#define MOTOR_CIRCUIT_PIN PA1 + +// +// Motor Protect +// +#define MOTOR_PROTECT_PIN PC0 + +// +// WiFi Reset +// +#define RESET_WIFI_PIN PB12 diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index d6d496624121..cb11c3e53b5b 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -28,7 +28,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Creality V4 only supports one hotend / E-stepper. Comment out this line to continue." + #error "Creality v4 only supports 1 hotend / E stepper." #endif #ifndef BOARD_INFO_NAME @@ -40,6 +40,13 @@ #define BOARD_NO_NATIVE_USB +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// +#ifndef DISABLE_DEBUG + #define DISABLE_DEBUG +#endif + // // EEPROM // @@ -51,9 +58,9 @@ #if ENABLED(IIC_BL24CXX_EEPROM) #define IIC_EEPROM_SDA PA11 #define IIC_EEPROM_SCL PA12 - #define MARLIN_EEPROM_SIZE 0x800 // 2Kb (24C16) + #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) #elif ENABLED(SDCARD_EEPROM_EMULATION) - #define MARLIN_EEPROM_SIZE 0x800 // 2Kb + #define MARLIN_EEPROM_SIZE 0x800 // 2K #endif // @@ -122,11 +129,6 @@ #endif #define E0_ENABLE_PIN X_ENABLE_PIN -// -// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role -// -#define DISABLE_DEBUG - // // Temperature Sensors // diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 7bf34441bcf4..484ff6544275 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -28,7 +28,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "CREALITY supports up to 1 hotends / E-steppers. Comment out this line to continue." + #error "Creality v4.2.10 only supports 1 hotend / E stepper." #endif #ifndef BOARD_INFO_NAME @@ -40,34 +40,24 @@ #define BOARD_NO_NATIVE_USB +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// +#define DISABLE_DEBUG + // // 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_PIN ? - - // 2K EEPROM - //#define SPI_EEPROM2_CS_PIN ? - - // 32Mb FLASH - //#define SPI_FLASH_CS_PIN ? + #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 +#endif +#if ENABLED(IIC_BL24CXX_EEPROM) + #define IIC_EEPROM_SDA PA11 + #define IIC_EEPROM_SCL PA12 + #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) +#else + #define SDCARD_EEPROM_EMULATION // SD EEPROM until all EEPROM is BL24CXX + #define MARLIN_EEPROM_SIZE 0x800 // 2K #endif // @@ -82,7 +72,9 @@ #define Y_STOP_PIN PA7 #define Z_STOP_PIN PA5 -#define Z_MIN_PROBE_PIN PA5 // BLTouch IN +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PA5 // BLTouch IN +#endif // // Filament Runout Sensor @@ -94,42 +86,37 @@ // // 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 X_ENABLE_PIN PC3 -#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 Y_ENABLE_PIN X_ENABLE_PIN -#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 Z_ENABLE_PIN X_ENABLE_PIN -#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 +#define E0_ENABLE_PIN X_ENABLE_PIN // // Temperature Sensors diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h index ced64e2a893c..4f57f8a805df 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h @@ -26,7 +26,7 @@ */ #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Creality v4.5.2 only supports one hotend / E-stepper. Comment out this line to continue." + #error "Creality v4.5.2 only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "Creality v4.5.2" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h index e7296d1ed077..6a0fa4f41802 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h @@ -26,7 +26,7 @@ */ #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Creality v4.5.3 only supports one hotend / E-stepper. Comment out this line to continue." + #error "Creality v4.5.3 only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "Creality v4.5.3" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h index 85d279872d55..a9ff02d1f4e2 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h @@ -47,9 +47,9 @@ #if ENABLED(IIC_BL24CXX_EEPROM) #define IIC_EEPROM_SDA PA11 #define IIC_EEPROM_SCL PA12 - #define MARLIN_EEPROM_SIZE 0x800 // 2Kb (24C16) + #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) #elif ENABLED(SDCARD_EEPROM_EMULATION) - #define MARLIN_EEPROM_SIZE 0x800 // 2Kb + #define MARLIN_EEPROM_SIZE 0x800 // 2K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h index 0682bfd73620..08c9500fc5e1 100644 --- a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h @@ -28,7 +28,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Eryone Ery32 mini supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "Eryone Ery32 mini supports up to 2 hotends / E steppers." #endif #ifndef BOARD_INFO_NAME @@ -41,7 +41,7 @@ #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define MARLIN_EEPROM_SIZE (EEPROM_PAGE_SIZE) #endif diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index 947e36c765e7..dd621eb5c126 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -32,7 +32,7 @@ #if NOT_TARGET(__STM32F1__, STM32F1xx) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "FLSUN HiSpeedV1 only supports one hotend / E-stepper. Comment out this line to continue." + #error "FLSUN HiSpeedV1 only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "FLSun HiSpeedV1" @@ -41,7 +41,7 @@ #define BOARD_NO_NATIVE_USB // Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 +#define TEMP_TIMER 5 // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role @@ -53,9 +53,9 @@ // #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif // @@ -92,7 +92,7 @@ #define Z_MAX_PIN PC4 // +Z #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN MT_DET_1_PIN + #define FIL_RUNOUT_PIN PA4 // MT_DET #endif // @@ -217,14 +217,14 @@ // #if ENABLED(PSU_CONTROL) #define KILL_PIN PA2 // PW_DET - #define KILL_PIN_STATE HIGH + #define KILL_PIN_STATE HIGH //#define PS_ON_PIN PA3 // PW_CN /PW_OFF #endif #if HAS_TFT_LVGL_UI #define MT_DET_1_PIN PA4 // MT_DET #define MT_DET_2_PIN PE6 - #define MT_DET_PIN_STATE LOW + #define MT_DET_PIN_STATE LOW #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 5468d0b4bd7c..952b40c1dedb 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -32,7 +32,7 @@ // #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE 0x800 // 2KB + #define EEPROM_PAGE_SIZE 0x800 // 2K #define EEPROM_START_ADDRESS (0x8000000 + 256 * 1024 - 2 * EEPROM_PAGE_SIZE) // 256K firmware space #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE #endif diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index fe6fd6fa5733..9250ee112762 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -40,9 +40,9 @@ // #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 08aeca8c5b59..beda50d29b1b 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -37,9 +37,9 @@ #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index 03547381c010..5515132c7844 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -53,7 +53,7 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index cb5200bc27da..dc23680b8c20 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -53,7 +53,7 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 88aa35f2c08b..4b5d38e8c544 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -58,7 +58,7 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index 12a6d5b84d7f..968d9cb6bd58 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -53,7 +53,7 @@ // Enable EEPROM Emulation for this board as it doesn't have EEPROM #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index beae0a3bf0b6..d3cf3e5cf52c 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -33,7 +33,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "JGAurora A5S A1 only supports one hotend / E-stepper. Comment out this line to continue." + #error "JGAurora A5S A1 only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "JGAurora A5S A1" @@ -53,9 +53,9 @@ #endif #if ENABLED(I2C_EEPROM) - //#define MARLIN_EEPROM_SIZE 0x8000UL // 32KB + //#define MARLIN_EEPROM_SIZE 0x8000UL // 32K #elif ENABLED(FLASH_EEPROM_EMULATION) - //#define MARLIN_EEPROM_SIZE 0x1000UL // 4KB + //#define MARLIN_EEPROM_SIZE 0x1000UL // 4K //#define MARLIN_EEPROM_SIZE (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL) #endif diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index ac11bd8b38b8..e6d31746539a 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -28,7 +28,7 @@ #if NOT_TARGET(__STM32F1__, STM32F1xx) #error "Oops! Select a STM32F1 board in 'Tools > Board.'" #elif HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Longer3D only supports one hotend / E-stepper. Comment out this line to continue." + #error "Longer3D only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "Longer3D" @@ -194,19 +194,19 @@ #define EEPROM_SCK_PIN BOARD_SPI1_SCK_PIN // PA5 pin 30 #define EEPROM_MISO_PIN BOARD_SPI1_MISO_PIN // PA6 pin 31 #define EEPROM_MOSI_PIN BOARD_SPI1_MOSI_PIN // PA7 pin 32 - #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) - #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64KB for now... + #define EEPROM_PAGE_SIZE 0x1000U // 4K (from datasheet) + #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64K for now... #elif HAS_SPI_FLASH - #define SPI_FLASH_SIZE 0x40000U // limit to 256KB (M993 will reboot with 512) + #define SPI_FLASH_SIZE 0x40000U // limit to 256K (M993 will reboot with 512) #define SPI_FLASH_CS_PIN PC5 #define SPI_FLASH_MOSI_PIN PA7 #define SPI_FLASH_MISO_PIN PA6 #define SPI_FLASH_SCK_PIN PA5 #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define MARLIN_EEPROM_SIZE (EEPROM_PAGE_SIZE) #else - #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM + #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2K, require this amount of RAM #endif diff --git a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h index 87526bac8797..f157c8e45544 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -28,7 +28,7 @@ #if NOT_TARGET(STM32F1, STM32F1xx) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 - #error "MPX ARM Mini only supports one hotend / E-stepper. Comment out this line to continue." + #error "MPX ARM Mini only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "Mingda MPX ARM Mini" @@ -46,16 +46,16 @@ #define I2C_EEPROM #undef NO_EEPROM_SELECTED -#define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#define MARLIN_EEPROM_SIZE 0x1000 // 4K #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_PAGE_SIZE 0x800U // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif #define SPI_DEVICE 2 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 150c18d79a1b..2c147eb9f3e0 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -29,7 +29,7 @@ #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." + #error "MKS Robin supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS Robin" @@ -53,7 +53,7 @@ #endif #if ENABLED(FLASH_EEPROM_EMULATION) - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define MARLIN_EEPROM_SIZE (EEPROM_PAGE_SIZE) #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h index 6b05bb7a7487..448e62ac8dad 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 HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "MKS Robin E3 only supports one hotend / E-stepper. Comment out this line to continue." + #error "MKS Robin E3 only supports 1 hotend / E stepper." #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 9d11af43ef2b..77c2b792157a 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 HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "MKS Robin E3D only supports one hotend / E-stepper. Comment out this line to continue." + #error "MKS Robin E3D only supports 1 hotend / E stepper." #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 index 930ef9722d50..2ad68a01405c 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h @@ -26,7 +26,7 @@ */ #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "MKS Robin E3D v1.1 only supports one hotend / E-stepper. Comment out this line to continue." + #error "MKS Robin E3D v1.1 only supports 1 hotend / E stepper." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 88c5d5f53c73..38f10f671359 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -28,7 +28,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "MKS Robin E3P only supports one hotend / E-stepper. Comment out this line to continue." + #error "MKS Robin E3P only supports 1 hotend / E stepper." #elif HAS_FSMC_TFT #error "MKS Robin E3P doesn't support FSMC-based TFT displays." #endif @@ -54,7 +54,7 @@ #if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM // EEPROM on I2C-0 - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // @@ -205,6 +205,34 @@ //#define LED_PIN PB2 +/** + * ------ ------ + * PC5 |10 9 | PE13 PA6 |10 9 | PA5 + * PD13 | 8 7 | PC6 PE8 | 8 7 | PE10 + * PE14 | 6 5 PE15 PE11 | 6 5 PA7 + * PD11 | 4 3 | PD10 PE12 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | 3.3V + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN PD10 +#define EXP1_04_PIN PD11 +#define EXP1_05_PIN PE15 +#define EXP1_06_PIN PE14 +#define EXP1_07_PIN PC6 +#define EXP1_08_PIN PD13 +#define EXP1_09_PIN PE13 +#define EXP1_10_PIN PC5 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PE12 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PE11 +#define EXP2_07_PIN PE10 +#define EXP2_08_PIN PE8 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + // // SD Card // @@ -219,11 +247,11 @@ #define ONBOARD_SD_CS_PIN PC11 #elif SD_CONNECTION_IS(LCD) #define ENABLE_SPI1 - #define SDSS PE10 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PE12 + #define SDSS EXP2_07_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_04_PIN #endif // @@ -240,27 +268,26 @@ // Shared SPI TFT - #define LCD_BACKLIGHT_PIN PD13 + #define LCD_BACKLIGHT_PIN EXP1_08_PIN - #define TOUCH_CS_PIN PE14 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI + #define TOUCH_CS_PIN EXP1_06_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_09_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_10_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_05_PIN // SPI1_MOSI - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 - #define BTN_ENC PE13 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN - #define TFT_CS_PIN PD11 - #define TFT_SCK_PIN PA5 - #define TFT_MISO_PIN PA6 - #define TFT_MOSI_PIN PA7 - #define TFT_DC_PIN PD10 - #define TFT_RST_PIN PC6 + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + #define TFT_DC_PIN EXP1_03_PIN #define TFT_A0_PIN TFT_DC_PIN - #define TFT_RESET_PIN PC6 - #define TFT_BACKLIGHT_PIN PD13 + #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 @@ -271,22 +298,22 @@ #if ENABLED(TFT_CLASSIC_UI) // Emulated DOGM SPI - #define LCD_PINS_ENABLE PD13 - #define LCD_PINS_RS PC6 - #define BTN_ENC PE13 - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #elif ENABLED(TFT_COLOR_UI) #define TFT_BUFFER_SIZE 14400 #endif #if HAS_WIRED_LCD && !HAS_SPI_TFT - #define BEEPER_PIN PC5 - #define BTN_ENC PE13 - #define LCD_PINS_ENABLE PD13 - #define LCD_PINS_RS PC6 - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #define LCD_BACKLIGHT_PIN -1 #if ENABLED(MKS_MINI_12864) @@ -296,18 +323,18 @@ #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 - #define DOGLCD_A0 PD11 - #define DOGLCD_CS PE15 - #define DOGLCD_SCK PA5 - #define DOGLCD_MOSI PA7 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define PIN_SPI_SCK PA5 - #define PIN_TFT_MISO PA6 - #define PIN_TFT_MOSI PA7 - #define TFTGLCD_CS PE8 + #define PIN_SPI_SCK EXP2_09_PIN + #define PIN_TFT_MISO EXP2_10_PIN + #define PIN_TFT_MOSI EXP2_05_PIN + #define TFTGLCD_CS EXP2_08_PIN #endif #ifndef BEEPER_PIN @@ -315,14 +342,14 @@ #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define LCD_PINS_DC PC6 - #define DOGLCD_CS PD13 + #define LCD_PINS_DC EXP1_07_PIN + #define DOGLCD_CS EXP1_08_PIN #define DOGLCD_A0 DOGLCD_A0 #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PE14 - #define NEOPIXEL_PIN PE15 - #define DOGLCD_MOSI PA7 - #define DOGLCD_SCK PA5 + #define LCD_RESET_PIN EXP1_06_PIN + #define NEOPIXEL_PIN EXP1_05_PIN + #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_SCK EXP2_09_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif @@ -330,11 +357,11 @@ #else // !MKS_MINI_12864 - #define LCD_PINS_D4 PE14 + #define LCD_PINS_D4 EXP1_06_PIN #if IS_ULTIPANEL - #define LCD_PINS_D5 PE15 - #define LCD_PINS_D6 PD11 - #define LCD_PINS_D7 PD10 + #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 @@ -360,7 +387,7 @@ #endif #ifndef BEEPER_PIN - #define BEEPER_PIN PC5 + #define BEEPER_PIN EXP1_10_PIN #endif #if ENABLED(SPEAKER) && BEEPER_PIN == PC5 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 index 7a38507c7621..13677b40a0ef 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h @@ -26,7 +26,7 @@ */ #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "MKS Robin E3 v1.1 only supports one hotend / E-stepper. Comment out this line to continue." + #error "MKS Robin E3 v1.1 only supports 1 hotend / E stepper." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h index 4eaf2e946939..31e034e025e9 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h @@ -27,7 +27,7 @@ // Onboard I2C EEPROM #if NO_EEPROM_SELECTED #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x1000// 4KB + #define MARLIN_EEPROM_SIZE 0x1000// 4K #undef NO_EEPROM_SELECTED #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index a1a822a9c2f3..4af88c18482a 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -40,9 +40,9 @@ // #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 9f33d4392a14..bc42bd02eba0 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -24,7 +24,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "MKS Robin Lite only supports one hotend / E-stepper. Comment out this line to continue." + #error "MKS Robin Lite only supports 1 hotend / E stepper." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h index 416a061412e1..b1aaa53c9487 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h @@ -28,7 +28,7 @@ #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." + #error "MKS Robin Lite3 supports up to 2 hotends / E steppers." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index c981fdc00a57..0bfc7f5c8d93 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -28,7 +28,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "MKS Robin mini only supports one hotend / E-stepper. Comment out this line to continue." + #error "MKS Robin mini only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "MKS Robin Mini" @@ -45,9 +45,9 @@ // #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif #define SPI_DEVICE 2 @@ -153,6 +153,9 @@ #define FSMC_CS_PIN PD7 // NE4 #define FSMC_RS_PIN PD11 // A0 + #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 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 07ee8c4fa060..9ce5d270b556 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -28,7 +28,7 @@ #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." + #error "MKS Robin nano supports up to 2 hotends / E steppers." #elif HAS_FSMC_TFT #error "MKS Robin nano v2 doesn't support FSMC-based TFT displays." #endif @@ -54,7 +54,7 @@ #if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM // EEPROM on I2C-0 - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // @@ -282,11 +282,10 @@ #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 TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h index e057e13c25f0..0eb7bbdffeb4 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS Robin nano supports up to 2 hotends / E-steppers. Comment out this line to continue." + #error "MKS Robin nano boards support up to 2 hotends / E steppers." #endif #define BOARD_NO_NATIVE_USB @@ -42,9 +42,9 @@ #endif #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif #define SPI_DEVICE 2 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 53f207adb7ab..1db2d0c5dd84 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -28,7 +28,7 @@ #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." + #error "MKS Robin pro supports up to 3 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS Robin pro" diff --git a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h index 7f4aa563b01c..ad28e5c47b64 100644 --- a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h +++ b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h @@ -33,9 +33,9 @@ #if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif // @@ -173,7 +173,9 @@ #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) - #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_E3_DIP.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_PANDA_PI_V29.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** FYSETC TFT TFT81050 display pinout * diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index 6c7e7cbbfa48..73f61c1aca70 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -31,7 +31,7 @@ #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." + #error "Trigorilla Pro supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Trigorilla Pro" @@ -51,10 +51,10 @@ #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 EEPROM_PAGE_SIZE (0x800U) // 2K, but will use 2x more (4K) #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE #else - #define MARLIN_EEPROM_SIZE (0x800U) // On SD, Limit to 2KB, require this amount of RAM + #define MARLIN_EEPROM_SIZE (0x800U) // On SD, Limit to 2K, require this amount of RAM #endif // diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h index b1e5f77d0e9f..f1f03a7dd789 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -30,9 +30,9 @@ #if NO_EEPROM_SELECTED #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_PAGE_SIZE (0x800) // 2K #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif //============================================================================= diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h index 49e9564b2738..17e13bdc87ba 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -30,9 +30,9 @@ #if NO_EEPROM_SELECTED #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_PAGE_SIZE (0x800) // 2K #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif //#define OPTION_DUALZ_DRIVE diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h index 295ab4c50ccc..df0eb9c3d812 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -30,9 +30,9 @@ #if NO_EEPROM_SELECTED #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_PAGE_SIZE (0x800) // 2K #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif //#define OPTION_DUALZ_DRIVE diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h index 43aefe97f51d..01ca4560fe4a 100644 --- a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h @@ -24,7 +24,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Anet ET4 only supports one hotend / E-stepper. Comment out this line to continue." + #error "Anet ET4 only supports 1 hotend / E stepper." #endif #ifndef BOARD_INFO_NAME @@ -39,7 +39,7 @@ #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) + //#define IIC_BL24CXX_EEPROM // Use I2C EEPROM onboard IC (AT24C04C, Size 4K, PageSize 16B) #endif #if ENABLED(FLASH_EEPROM_EMULATION) @@ -50,7 +50,7 @@ #define IIC_EEPROM_SDA PB11 #define IIC_EEPROM_SCL PB10 #define EEPROM_DEVICE_ADDRESS 0xA0 - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // @@ -64,7 +64,7 @@ // 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." + #error "You will need to use 24V to 5V converter and remove one resistor and capacitor from the motherboard. See https://bit.ly/3xg9cXO 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 diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index 7cccac7caa3a..d08d3fb66c0a 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -27,7 +27,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Arm'ed supports up to 2 hotends / E-steppers." + #error "Arm'ed supports up to 2 hotends / E steppers." #endif #ifndef ARMED_V1_0 @@ -40,7 +40,7 @@ #if NO_EEPROM_SELECTED #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // @@ -150,7 +150,7 @@ #if ENABLED(FYSETC_MINI_12864) // - // See https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 + // See https://wiki.fysetc.com/Mini12864_Panel/ // #define DOGLCD_A0 PE9 #define DOGLCD_CS PE8 diff --git a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h index 7a60f4aa0220..47d009c5a61e 100644 --- a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h +++ b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h @@ -24,7 +24,7 @@ #include "env_validate.h" #if HOTENDS > 1 || E_STEPPERS > 1 - #error "Artillery Ruby supports up to 1 hotends / E-steppers." + #error "Artillery Ruby only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "Artillery Ruby" @@ -33,7 +33,7 @@ #define FLASH_EEPROM_EMULATION //#define I2C_EEPROM #endif -//#define E2END 0xFFF // 4KB +//#define E2END 0xFFF // 4K #define HAL_TIMER_RATE F_CPU diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index 061680aa79cd..c49abca9ef85 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -31,7 +31,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "Black STM32F4VET6 supports up to 2 hotends / E-steppers." + #error "Black STM32F4VET6 supports up to 2 hotends / E steppers." #endif #ifndef BOARD_INFO_NAME @@ -42,7 +42,7 @@ //#define I2C_EEPROM #define SRAM_EEPROM_EMULATION -#define MARLIN_EEPROM_SIZE 0x2000 // 8KB +#define MARLIN_EEPROM_SIZE 0x2000 // 8K // // Servos 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 99de2e43e7a3..531ab7a9581d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -24,7 +24,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "BIGTREE BTT002 V1.0 only supports one hotend / E-stepper. Comment out this line to continue." + #error "BIGTREE BTT002 V1.0 only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "BTT BTT002 V1.0" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index 554b2704c7df..c7cd35c7ad85 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -36,7 +36,7 @@ // Onboard I2C EEPROM #define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#define MARLIN_EEPROM_SIZE 0x1000 // 4K // // Servos @@ -211,7 +211,9 @@ #if ENABLED(LCD_FOR_MELZI) - #error "CAUTION! LCD_FOR_MELZI requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! LCD_FOR_MELZI requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** LCD_FOR_MELZI display pinout * @@ -245,7 +247,9 @@ #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif #define LCD_PINS_RS PE10 #define LCD_PINS_ENABLE PE9 @@ -273,7 +277,9 @@ #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * TFTGLCD_PANEL_SPI display pinout @@ -327,7 +333,9 @@ #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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** FYSETC TFT TFT81050 display pinout * 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 7db6c4922e88..b9525a9267ab 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -26,7 +26,7 @@ #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." + #error "BIGTREE GTR V1.0 supports up to 8 hotends / E steppers." #endif #define BOARD_INFO_NAME "BTT GTR V1.0" @@ -37,7 +37,7 @@ // Onboard I2C EEPROM #define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x2000 // 8KB (24C64 ... 64Kb = 8KB) +#define MARLIN_EEPROM_SIZE 0x2000 // 8K (24C64) // // Servos diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 8652a815c21b..4255881baf86 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -28,7 +28,7 @@ // Onboard I2C EEPROM #define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x8000 // 32KB (24C32A) +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB (AT24C32) #define I2C_SCL_PIN PB8 #define I2C_SDA_PIN PB9 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h index fb4b17b6fb22..8a918835f75e 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_1.h @@ -22,7 +22,7 @@ #pragma once #if HOTENDS > 3 || E_STEPPERS > 3 - #error "BIGTREE SKR Pro V1.1 supports up to 3 hotends / E-steppers." + #error "BIGTREE SKR Pro V1.1 supports up to 3 hotends / E steppers." #endif #define BOARD_INFO_NAME "BTT SKR Pro V1.1" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_2.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_2.h index 615751b62d37..c88483f73ed4 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_2.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_V1_2.h @@ -22,7 +22,7 @@ #pragma once #if HOTENDS > 3 || E_STEPPERS > 3 - #error "BIGTREE SKR Pro V1.2 supports up to 3 hotends / E-steppers." + #error "BIGTREE SKR Pro V1.2 supports up to 3 hotends / E steppers." #endif #define BOARD_INFO_NAME "BTT SKR Pro V1.2" 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 5e424d4105fb..7c902b008cf6 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -456,7 +456,9 @@ #elif ENABLED(WYH_L12864) - #error "CAUTION! WYH_L12864 requires wiring modifications. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! WYH_L12864 requires wiring modifications. See 'pins_BTT_SKR_PRO_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index d526c75b6396..4e311d48628a 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -527,6 +527,11 @@ #endif #if HAS_SPI_TFT + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN + // // e.g., BTT_TFT35_SPI_V1_0 (480x320, 3.5", SPI Stock Display with Rotary Encoder in BIQU B1 SE) // @@ -542,9 +547,6 @@ #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 // diff --git a/Marlin/src/HAL/ESP32/watchdog.h b/Marlin/src/pins/stm32f4/pins_CREALITY_V24S1_301F4.h similarity index 64% rename from Marlin/src/HAL/ESP32/watchdog.h rename to Marlin/src/pins/stm32f4/pins_CREALITY_V24S1_301F4.h index 43db8130763f..883640d5772e 100644 --- a/Marlin/src/HAL/ESP32/watchdog.h +++ b/Marlin/src/pins/stm32f4/pins_CREALITY_V24S1_301F4.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,18 +21,18 @@ */ #pragma once -#ifdef __cplusplus - extern "C" { -#endif - - esp_err_t esp_task_wdt_reset(); +/** + * Creality V24S1_301F4 (STM32F401RC) board pin assignments as found on Ender 3 S1. + */ -#ifdef __cplusplus - } +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Creality V24S1-301F4" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "Ender-3 S1 F4" #endif -// Initialize watchdog with a 4 second interrupt time -void watchdog_init(); +#define DISABLE_DEBUG false // DISABLE_(DEBUG|JTAG) is not supported for STM32F4. +#define ALLOW_STM32F4 -// Reset watchdog. -inline void HAL_watchdog_refresh() { esp_task_wdt_reset(); } +#include "../stm32f1/pins_CREALITY_V24S1_301.h" diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 514fad4b8924..11b5dbbb6cc4 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -25,7 +25,7 @@ #include "env_validate.h" #if HOTENDS > 6 || E_STEPPERS > 6 - #error "FLYF407ZG supports up to 6 hotends / E-steppers." + #error "FLYF407ZG supports up to 6 hotends / E steppers." #endif #define BOARD_INFO_NAME "FLYF407ZG" @@ -50,11 +50,11 @@ // the 128kB sector allocated for EEPROM emulation. #define FLASH_EEPROM_LEVELING #elif ENABLED(I2C_EEPROM) - #define MARLIN_EEPROM_SIZE 0x2000 // 8KB + #define MARLIN_EEPROM_SIZE 0x2000 // 8K #endif #ifndef MARLIN_EEPROM_SIZE - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index dfcb4217c9db..3ed18f9abc68 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -24,7 +24,7 @@ #include "env_validate.h" #if HOTENDS > 3 || E_STEPPERS > 3 - #error "FYSETC S6 supports up to 3 hotends / E-steppers." + #error "FYSETC S6 supports up to 3 hotends / E steppers." #endif #ifndef BOARD_INFO_NAME @@ -50,7 +50,7 @@ // 128 kB sector allocated for EEPROM emulation. #define FLASH_EEPROM_LEVELING #elif ENABLED(I2C_EEPROM) - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h index e05811552e2b..009bfb248dfe 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h @@ -39,7 +39,7 @@ #endif #if ENABLED(I2C_EEPROM) - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // @@ -117,7 +117,7 @@ #endif #if HOTENDS > 3 || E_STEPPERS > 3 - #error "FYSETC SPIDER supports up to 3 hotends / E-steppers." + #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_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 099b3b79a497..6c6f8d25ea39 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -25,7 +25,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "LERDGE K supports up to 2 hotends / E-steppers." + #error "LERDGE K supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Lerdge K" diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index e4fc97170c44..376c2f3f2734 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -25,7 +25,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "LERDGE S supports up to 2 hotends / E-steppers." + #error "LERDGE S supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "Lerdge S" @@ -186,15 +186,15 @@ #define EEPROM_SCK_PIN PB13 // datasheet: CLK pin, found with multimeter, not tested #define EEPROM_MISO_PIN PB14 // datasheet: DO pin, found with multimeter, not tested #define EEPROM_MOSI_PIN PB15 // datasheet: DI pin, found with multimeter, not tested - #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) - #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64KB for now... + #define EEPROM_PAGE_SIZE 0x1000U // 4K (from datasheet) + #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64K for now... #elif ENABLED(I2C_EEPROM) // FM24CL64BG (CYP1813) 64Kbit F-RAM #define SOFT_I2C_EEPROM // Force the use of Software I2C #define I2C_SDA_PIN PG13 #define I2C_SCL_PIN PG14 // To be confirmed on the Lerdge S, but probably same as the K - #define MARLIN_EEPROM_SIZE 0x10000 + #define MARLIN_EEPROM_SIZE 0x2000U // 8K #else - #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM + #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2K, require this amount of RAM #endif // diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index 5048933146fe..6325697655ee 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -25,7 +25,7 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "LERDGE X only supports one hotend / E-stepper. Comment out this line to continue." + #error "LERDGE X only supports 1 hotend / E stepper." #endif #define BOARD_INFO_NAME "Lerdge X" diff --git a/Marlin/src/pins/stm32f4/pins_MKS_EAGLE.h b/Marlin/src/pins/stm32f4/pins_MKS_EAGLE.h index 50f06b7e8119..ecea8e182b9e 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_EAGLE.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_EAGLE.h @@ -25,7 +25,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS Eagle supports up to 2 hotends / E-steppers." + #error "MKS Eagle supports up to 2 hotends / E steppers." #elif HAS_FSMC_TFT #error "MKS Eagle doesn't support FSMC-based TFT displays." #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index af71f0d562c8..e55f3170d03e 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -25,7 +25,7 @@ #include "env_validate.h" #if HOTENDS > 3 || E_STEPPERS > 5 - #error "MKS Monster supports up to 3 hotends and 5 E-steppers." + #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 @@ -44,7 +44,7 @@ //#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 MARLIN_EEPROM_SIZE 0x1000 // 4K #define I2C_SCL_PIN PB8 // I2C_SCL and CAN_RX #define I2C_SDA_PIN PB9 // I2C_SDA and CAN_TX @@ -289,16 +289,16 @@ #define TFT_MISO_PIN EXP2_10_PIN #define TFT_MOSI_PIN EXP2_05_PIN #define TFT_DC_PIN EXP1_03_PIN - #define TFT_RST_PIN EXP1_07_PIN #define TFT_A0_PIN TFT_DC_PIN #define TFT_RESET_PIN EXP1_07_PIN - #define TFT_BACKLIGHT_PIN EXP1_08_PIN + + #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #define LCD_BACKLIGHT_PIN EXP1_08_PIN #ifndef TFT_WIDTH #define TFT_WIDTH 480 #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h index 589300f34175..2274d0c0dff3 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h @@ -24,7 +24,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS_ROBIN2 supports up to 2 hotends / E-steppers." + #error "MKS_ROBIN2 supports up to 2 hotends / E steppers." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 02140865f96a..32d8a47488b9 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -25,7 +25,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS Robin Nano V3 supports up to 2 hotends / E-steppers." + #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 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h index 032ce41bcb2f..989010e47f36 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h @@ -36,7 +36,7 @@ //#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation #if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #define I2C_SCL_PIN PB6 #define I2C_SDA_PIN PB7 #endif @@ -119,6 +119,14 @@ #define TEMP_1_PIN PA2 // TH2 #define TEMP_BED_PIN PC0 // TB1 +#if HOTENDS == 1 && !REDUNDANT_TEMP_MATCH(SOURCE, E1) + #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 // @@ -275,16 +283,16 @@ #define TFT_MISO_PIN EXP2_10_PIN #define TFT_MOSI_PIN EXP2_05_PIN #define TFT_DC_PIN EXP1_03_PIN - #define TFT_RST_PIN EXP1_07_PIN #define TFT_A0_PIN TFT_DC_PIN #define TFT_RESET_PIN EXP1_07_PIN - #define TFT_BACKLIGHT_PIN EXP1_08_PIN + + #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #define LCD_BACKLIGHT_PIN EXP1_08_PIN #ifndef TFT_WIDTH #define TFT_WIDTH 480 #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 68b238525477..1627bb909b4c 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -25,7 +25,7 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS Robin Nano V3 supports up to 1 hotends / E-steppers." + #error "MKS Robin Nano V3 supports up to 2 hotends / E steppers." #endif #define BOARD_INFO_NAME "MKS Robin PRO V2" @@ -37,7 +37,7 @@ //#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 MARLIN_EEPROM_SIZE 0x1000 // 4K #define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support @@ -305,16 +305,15 @@ #define TFT_MISO_PIN EXP2_10_PIN #define TFT_MOSI_PIN EXP2_05_PIN #define TFT_DC_PIN EXP1_03_PIN - #define TFT_RST_PIN EXP1_07_PIN #define TFT_A0_PIN TFT_DC_PIN #define TFT_RESET_PIN EXP1_07_PIN - #define TFT_BACKLIGHT_PIN EXP1_08_PIN + #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #define LCD_BACKLIGHT_PIN EXP1_08_PIN #ifndef TFT_WIDTH #define TFT_WIDTH 480 #endif diff --git a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h similarity index 96% rename from Marlin/src/pins/stm32f4/pins_INDEX_REV03.h rename to Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h index 977f4763437c..36dde8810525 100644 --- a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h +++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h @@ -22,15 +22,15 @@ #pragma once /** - * STM32F407VET6 on Index PnP Mobo Rev03 - * Website - https://indexmachines.io/ + * STM32F407VET6 on Opulo Lumen PnP Rev3 + * Website - https://opulo.io/ */ #define ALLOW_STM32DUINO #include "env_validate.h" -#define BOARD_INFO_NAME "Index Mobo Rev03" -#define DEFAULT_MACHINE_NAME "Index Pick and Place" +#define BOARD_INFO_NAME "Opulo Lumen REV3" +#define DEFAULT_MACHINE_NAME "Opulo Pick-and-Place" /** * By default, the extra stepper motor configuration is: @@ -40,7 +40,7 @@ */ #define SRAM_EEPROM_EMULATION -#define MARLIN_EEPROM_SIZE 0x2000 // 8KB +#define MARLIN_EEPROM_SIZE 0x2000 // 8K // I2C MCP3426 (16-Bit, 240SPS, dual-channel ADC) #define HAS_MCP3426_ADC diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h index f2073457b13b..e926a2b0c6a4 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h @@ -33,10 +33,10 @@ #if NO_EEPROM_SELECTED #if MB(RUMBA32_V1_0) #define FLASH_EEPROM_EMULATION - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #elif MB(RUMBA32_V1_1) #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x2000 // 8KB (24LC64T-I/OT) + #define MARLIN_EEPROM_SIZE 0x2000 // 8K (24LC64T-I/OT) #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h index 28d2dfd1806f..2f3e121fe17a 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h @@ -30,7 +30,7 @@ #if NO_EEPROM_SELECTED #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB (24LC32AT-I/OT) + #define MARLIN_EEPROM_SIZE 0x1000 // 4K (24LC32AT-I/OT) #endif #if ENABLED(FLASH_EEPROM_EMULATION) diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h index 0b539417d6d0..3833a3a007a9 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h @@ -37,7 +37,7 @@ #if NO_EEPROM_SELECTED #define FLASH_EEPROM_EMULATION - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif #if ENABLED(FLASH_EEPROM_EMULATION) diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 873a4d4ad382..12871becbb40 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -28,7 +28,7 @@ #include "env_validate.h" #if HOTENDS > 3 || E_STEPPERS > 3 - #error "RUMBA32 boards support up to 3 hotends / E-steppers." + #error "RUMBA32 boards support up to 3 hotends / E steppers." #endif #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index fd6b96054214..1439e6de651c 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -34,7 +34,7 @@ // Onboard I2C EEPROM #if NO_EEPROM_SELECTED #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #define I2C_SCL_PIN PB6 #define I2C_SDA_PIN PB7 #undef NO_EEPROM_SELECTED diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index c6b24f9eca61..66caec588f60 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -25,14 +25,14 @@ #include "env_validate.h" #if HOTENDS > 2 || E_STEPPERS > 2 - #error "STM32F4 supports up to 2 hotends / E-steppers." + #error "STM32F4 VAkE supports up to 2 hotends / E steppers." #endif #define DEFAULT_MACHINE_NAME "STM32F446VET6" #define BOARD_INFO_NAME "STM32F4 VAkE" //#define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#define MARLIN_EEPROM_SIZE 0x1000 // 4K // // Servos @@ -161,27 +161,61 @@ #define POWER_LOSS_PIN PA4 // ?? Power loss / nAC_FAULT #if ENABLED(SDSUPPORT) - #define SD_DETECT_PIN PB7 - #define SD_SS_PIN PB_15 // USD_CS -> CS for onboard SD + #define SD_DETECT_PIN EXP2_04_PIN + #define SD_SS_PIN PB15 // USD_CS -> CS for onboard SD #endif +/** + * ------ ------ + * PC9 |10 9 | PB12 ? |10 9 | ? + * PD7 | 8 7 | PC12 PD6 | 8 7 | ? + * PD1 | 6 5 PD2 PD0 | 6 5 ? + * PD3 | 4 3 | PD4 PB7 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | 3.3V + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN PD4 +#define EXP1_04_PIN PD3 +#define EXP1_05_PIN PD2 +#define EXP1_06_PIN PD1 +#define EXP1_07_PIN PC12 +#define EXP1_08_PIN PD7 +#define EXP1_09_PIN PB12 +#define EXP1_10_PIN PC9 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PB7 +//#define EXP2_05_PIN ? +#define EXP2_06_PIN PD0 +//#define EXP2_07_PIN ? +#define EXP2_08_PIN PD6 +//#define EXP2_09_PIN ? +//#define EXP2_10_PIN ? + // // LCD / Controller // #if HAS_WIRED_LCD + #if ENABLED(SDSUPPORT) #define SDSS PB6 // CS for SD card in LCD #endif - #define BEEPER_PIN PC9 - #define LCD_PINS_RS PC12 - #define LCD_PINS_ENABLE PD7 - #define LCD_PINS_D4 PD1 - #define LCD_PINS_D5 PD2 - #define LCD_PINS_D6 PD3 - #define LCD_PINS_D7 PD4 - #define BTN_EN1 PD6 - #define BTN_EN2 PD0 - #define BTN_ENC PB12 + + #define BEEPER_PIN EXP1_10_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_07_PIN + + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index 5bfc2551acfa..c4feba692fd8 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 HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "RemRam only supports one hotend / E-stepper. Comment out this line to continue." + #error "RemRam only supports 1 hotend / E stepper." #endif // diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h index 2fddb68a7c0c..769f10c8a48b 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -41,7 +41,7 @@ #define SOFT_I2C_EEPROM // Force the use of Software I2C #define I2C_SCL_PIN PB6 #define I2C_SDA_PIN PB7 - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // @@ -170,7 +170,9 @@ * 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." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! DWIN_CREALITY_LCD requires a custom cable, see diagram above this line. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif #define BEEPER_PIN EXP1_09_PIN #define BTN_EN1 EXP1_03_PIN @@ -193,7 +195,9 @@ #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif #define LCD_PINS_RS PB9 #define LCD_PINS_ENABLE EXP1_09_PIN @@ -221,7 +225,9 @@ #if ENABLED(TFTGLCD_PANEL_SPI) - #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * TFTGLCD_PANEL_SPI display pinout @@ -258,7 +264,9 @@ #elif ENABLED(FYSETC_MINI_12864_2_1) - #error "CAUTION! FYSETC_MINI_12864_2_1 and clones require wiring modifications. See 'pins_BTT_SKR_MINI_E3_V3_0.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! FYSETC_MINI_12864_2_1 and clones require wiring modifications. See 'pins_BTT_SKR_MINI_E3_V3_0.h' for details. Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning" + #endif /** * @@ -307,7 +315,9 @@ #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) - #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif /** * FYSETC TFT TFT81050 display pinout diff --git a/Marlin/src/HAL/TEENSY40_41/watchdog.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_V2.h similarity index 80% rename from Marlin/src/HAL/TEENSY40_41/watchdog.h rename to Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_V2.h index 03ab151b0706..8be6dadee43b 100644 --- a/Marlin/src/HAL/TEENSY40_41/watchdog.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_V2.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,10 +21,8 @@ */ #pragma once -/** - * HAL Watchdog for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A) - */ +#define BOARD_INFO_NAME "BTT SKR SE BX V2.0" -void watchdog_init(); +#define SAFE_POWER_PIN PI11 -void HAL_watchdog_refresh(); +#include "pins_BTT_SKR_SE_BX_common.h" diff --git a/Marlin/src/HAL/NATIVE_SIM/watchdog.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_V3.h similarity index 83% rename from Marlin/src/HAL/NATIVE_SIM/watchdog.h rename to Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_V3.h index 4e404c3887da..8d8143ee622b 100644 --- a/Marlin/src/HAL/NATIVE_SIM/watchdog.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_V3.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,7 +21,6 @@ */ #pragma once -#define WDT_TIMEOUT 4000000 // 4 second timeout +#define BOARD_INFO_NAME "BTT SKR SE BX V3.0" -void watchdog_init(); -void HAL_watchdog_refresh(); +#include "pins_BTT_SKR_SE_BX_common.h" diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h similarity index 95% rename from Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h rename to Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h index 9eb0acf1448d..1ee7846c9315 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h @@ -25,14 +25,14 @@ #error "Oops! Select an STM32H7 board in 'Tools > Board.'" #endif -#define BOARD_INFO_NAME "BTT SKR SE BX" -#define DEFAULT_MACHINE_NAME "BIQU-BX" +#define DEFAULT_MACHINE_NAME "Biqu BX" // Onboard I2C EEPROM #define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x1000 // 4KB (24C32 ... 32Kb = 4KB) +#define MARLIN_EEPROM_SIZE 0x1000 // 4K (24C32) #define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support +//#define SWD_DEBUG // Use pins PA13 and PA14 on STM32H7 for the SWD debugger // // Limit Switches @@ -47,15 +47,14 @@ #define FIL_RUNOUT_PIN PD13 #define FIL_RUNOUT2_PIN PB13 -#define LED_PIN PA13 -#define BEEPER_PIN PA14 - -#define TFT_BACKLIGHT_PIN PB5 +#ifndef SWD_DEBUG + #define LED_PIN PA13 + #define BEEPER_PIN PA14 +#endif #define POWER_MONITOR_PIN PB0 #define RPI_POWER_PIN PE5 -#define SAFE_POWER_PIN PI11 #define SERVO0_PIN PA2 // diff --git a/Marlin/src/HAL/STM32/watchdog.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0.h similarity index 85% rename from Marlin/src/HAL/STM32/watchdog.h rename to Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0.h index 49a0d9c631d8..d83548608585 100644 --- a/Marlin/src/HAL/STM32/watchdog.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,5 +21,6 @@ */ #pragma once -void watchdog_init(); -void HAL_watchdog_refresh(); +#define BOARD_INFO_NAME "BTT SKR V3" + +#include "pins_BTT_SKR_V3_0_common.h" diff --git a/Marlin/src/HAL/LINUX/watchdog.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_EZ.h similarity index 85% rename from Marlin/src/HAL/LINUX/watchdog.h rename to Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_EZ.h index 49a0d9c631d8..003f20f5cf6e 100644 --- a/Marlin/src/HAL/LINUX/watchdog.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_EZ.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,5 +21,6 @@ */ #pragma once -void watchdog_init(); -void HAL_watchdog_refresh(); +#define BOARD_INFO_NAME "BTT SKR V3 EZ" + +#include "pins_BTT_SKR_V3_0_common.h" diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h new file mode 100644 index 000000000000..02e195a1852e --- /dev/null +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h @@ -0,0 +1,569 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +// 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 + +#define USES_DIAG_JUMPERS + +// Onboard I2C EEPROM +#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) + #undef NO_EEPROM_SELECTED + #define I2C_EEPROM + #define SOFT_I2C_EEPROM // Force the use of Software I2C + #define I2C_SCL_PIN PA14 + #define I2C_SDA_PIN PA13 + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +// +// 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 PC13 +#endif + +// +// Probe enable +// +#if ENABLED(PROBE_ENABLE_DISABLE) + #ifndef PROBE_ENABLE_PIN + #define PROBE_ENABLE_PIN SERVO0_PIN + #endif +#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 PE4 // PS-ON +#endif + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PC15 // PWRDET +#endif + +// +// Steppers +// +#define X_STEP_PIN PD4 +#define X_DIR_PIN PD3 +#define X_ENABLE_PIN PD6 +#ifndef X_CS_PIN + #define X_CS_PIN PD5 +#endif + +#define Y_STEP_PIN PA15 +#define Y_DIR_PIN PA8 +#define Y_ENABLE_PIN PD1 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD0 +#endif + +#define Z_STEP_PIN PE2 +#define Z_DIR_PIN PE3 +#define Z_ENABLE_PIN PE0 +#ifndef Z_CS_PIN + #define Z_CS_PIN PE1 +#endif + +#ifndef E0_STEP_PIN + #define E0_STEP_PIN PD15 +#endif +#ifndef E0_DIR_PIN + #define E0_DIR_PIN PD14 +#endif +#ifndef E0_ENABLE_PIN + #define E0_ENABLE_PIN PC7 +#endif +#ifndef E0_CS_PIN + #define E0_CS_PIN PC6 +#endif + +#ifndef E1_STEP_PIN + #define E1_STEP_PIN PD11 +#endif +#ifndef E1_DIR_PIN + #define E1_DIR_PIN PD10 +#endif +#ifndef E1_ENABLE_PIN + #define E1_ENABLE_PIN PD13 +#endif +#ifndef E1_CS_PIN + #define E1_CS_PIN PD12 +#endif + +// +// Temperature Sensors +// +#ifndef TEMP_0_PIN + #define TEMP_0_PIN PA2 // TH0 +#endif +#ifndef TEMP_1_PIN + #define TEMP_1_PIN PA3 // TH1 +#endif +#ifndef TEMP_BED_PIN + #define TEMP_BED_PIN PA1 // TB +#endif + +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) + #if TEMP_SENSOR_PROBE + #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 + +#if HAS_CUTTER + #ifndef SPINDLE_LASER_PWM_PIN + #define SPINDLE_LASER_PWM_PIN PB5 + #endif + #ifndef SPINDLE_LASER_ENA_PIN + #define SPINDLE_LASER_ENA_PIN PB6 + #endif +#else + #ifndef FAN1_PIN + #define FAN1_PIN PB6 // Fan1 + #endif + #ifndef FAN2_PIN + #define FAN2_PIN PB5 // Fan2 + #endif +#endif // SPINDLE_FEATURE || LASER_FEATURE + +// +// Software SPI pins for TMC2130 stepper drivers +// +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI PE13 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO PE15 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK PE14 + #endif +#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 X_SERIAL_TX_PIN + + #define Y_SERIAL_TX_PIN PD0 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + + #define Z_SERIAL_TX_PIN PE1 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + + #define E0_SERIAL_TX_PIN PC6 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + + #define E1_SERIAL_TX_PIN PD12 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// SD Connection +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +/** + * ------ ------ + * (BEEPER) PC5 |10 9 | PB0 (BTN_ENC) (MISO) PA6 |10 9 | PA5 (SCK) + * (LCD_EN) PB1 | 8 7 | PE8 (LCD_RS) (BTN_EN1) PE7 | 8 7 | PA4 (SD_SS) + * (LCD_D4) PE9 | 6 5 PE10 (LCD_D5) (BTN_EN2) PB2 | 6 5 PA7 (MOSI) + * (LCD_D6) PE11 | 4 3 | PE12 (LCD_D7) (SD_DETECT) PC4 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN PE12 +#define EXP1_04_PIN PE11 +#define EXP1_05_PIN PE10 +#define EXP1_06_PIN PE9 +#define EXP1_07_PIN PE8 +#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(LCD) + #define SDSS EXP2_07_PIN + #define SD_SS_PIN SDSS + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_04_PIN +#elif SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT + #define SDIO_CLOCK 24000000 // 24MHz +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "No custom SD drive cable defined for this board." +#endif + +#if ENABLED(BTT_MOTOR_EXPANSION) + /** ----- ----- + * -- | . . | GND -- | . . | GND + * -- | . . | 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 + + #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 IS_U8GLIB_ST7920 + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 120 + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 80 + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 580 + #endif +#endif + +#if HAS_SPI_TFT + // + // e.g., BTT_TFT35_SPI_V1_0 (480x320, 3.5", SPI Stock Display with Rotary Encoder in BIQU B1 SE) + // + #define TFT_CS_PIN EXP2_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 + +// +// 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 | -- + * -- | 14 | | 3 | 3.3V (ESP-EN) + * (ESP-RX) PD8 | 15 | | 2 | -- + * (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/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 3402bfaee382..2d84c95a3d19 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -249,7 +249,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi const millis_t init_timeout = millis() + SD_INIT_TIMEOUT; uint32_t arg; - watchdog_refresh(); // In case init takes too long + hal.watchdog_refresh(); // In case init takes too long // Set pin modes #if ENABLED(ZONESTAR_12864OLED) @@ -270,7 +270,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi // Must supply min of 74 clock cycles with CS high. LOOP_L_N(i, 10) spiSend(0xFF); - watchdog_refresh(); // In case init takes too long + hal.watchdog_refresh(); // In case init takes too long // Command to go idle in SPI mode while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) { @@ -284,7 +284,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi crcSupported = (cardCommand(CMD59, 1) == R1_IDLE_STATE); #endif - watchdog_refresh(); // In case init takes too long + hal.watchdog_refresh(); // In case init takes too long // check SD version for (;;) { @@ -306,7 +306,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi } } - watchdog_refresh(); // In case init takes too long + hal.watchdog_refresh(); // In case init takes too long // Initialize card and send host supports SDHC if SD2 arg = type() == SD_CARD_TYPE_SD2 ? 0x40000000 : 0; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index ec5f1a970913..3fff79653933 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -171,7 +171,7 @@ CardReader::CardReader() { workDirDepth = 0; ZERO(workDirParents); - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) + #if BOTH(SDSUPPORT, HAS_SD_DETECT) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif @@ -456,10 +456,11 @@ void CardReader::mount() { if (flag.mounted) cdroot(); - #if ENABLED(USB_FLASH_DRIVE_SUPPORT) || PIN_EXISTS(SD_DETECT) - else if (marlin_state != MF_INITIALIZING) - LCD_ALERTMESSAGE(MSG_MEDIA_INIT_FAIL); - #endif + else { + #if EITHER(HAS_SD_DETECT, USB_FLASH_DRIVE_SUPPORT) + if (marlin_state != MF_INITIALIZING) LCD_ALERTMESSAGE(MSG_MEDIA_INIT_FAIL); + #endif + } ui.refresh(); } @@ -472,22 +473,22 @@ void CardReader::mount() { #endif void CardReader::manage_media() { - static uint8_t prev_stat = 2; // First call, no prior state + static uint8_t prev_stat = 2; // At boot we don't know if media is present or not uint8_t stat = uint8_t(IS_SD_INSERTED()); - if (stat == prev_stat) return; - - DEBUG_SECTION(mm, "CardReader::manage_media", true); - DEBUG_ECHOLNPGM("SD Status ", prev_stat, " -> ", stat); + if (stat == prev_stat) return; // Already checked and still no change? - flag.workDirIsRoot = true; // Return to root on mount/release + DEBUG_SECTION(cmm, "CardReader::manage_media()", true); + DEBUG_ECHOLNPGM("Media present: ", prev_stat, " -> ", stat); if (!ui.detected()) { DEBUG_ECHOLNPGM("SD: No UI Detected."); return; } - uint8_t old_stat = prev_stat; - prev_stat = stat; // Change now to prevent re-entry + flag.workDirIsRoot = true; // Return to root on mount/release/init + + const uint8_t old_stat = prev_stat; + prev_stat = stat; // Change now to prevent re-entry in safe_delay if (stat) { // Media Inserted safe_delay(500); // Some boards need a delay to get settled @@ -499,21 +500,20 @@ void CardReader::manage_media() { TERN_(RESET_STEPPERS_ON_MEDIA_INSERT, reset_stepper_drivers()); // Workaround for Cheetah bug } else { - #if PIN_EXISTS(SD_DETECT) - release(); // Card is released - #endif + TERN_(HAS_SD_DETECT, release()); // Card is released } - ui.media_changed(old_stat, stat); // Update the UI + ui.media_changed(old_stat, stat); // Update the UI or flag an error if (!stat) return; // Exit if no media is present - TERN_(SDCARD_EEPROM_EMULATION, settings.first_load()); - if (old_stat != 2) return; // First mount? DEBUG_ECHOLNPGM("First mount."); + // Load settings the first time media is inserted (not just during init) + TERN_(SDCARD_EEPROM_EMULATION, settings.first_load()); + bool do_auto = true; UNUSED(do_auto); // Check for PLR file. diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 483ab8139584..d2f462c2a777 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -362,7 +362,7 @@ class CardReader { #if ENABLED(USB_FLASH_DRIVE_SUPPORT) #define IS_SD_INSERTED() DiskIODriver_USBFlash::isInserted() -#elif PIN_EXISTS(SD_DETECT) +#elif HAS_SD_DETECT #define IS_SD_INSERTED() (READ(SD_DETECT_PIN) == SD_DETECT_STATE) #else // No card detect line? Assume the card is inserted. diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp index a681af4efa63..7d698247e565 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp @@ -62,7 +62,7 @@ #define USB_HOST_MANUAL_POLL // Optimization to shut off IRQ automatically // Workarounds to keep Marlin's watchdog timer from barking... - void marlin_yield() { thermalManager.manage_heater(); } + void marlin_yield() { thermalManager.task(); } #define SYSTEM_OR_SPECIAL_YIELD(...) marlin_yield(); #define delay(x) safe_delay(x) diff --git a/README.md b/README.md index 8b623b382e78..f687ea6fc161 100644 --- a/README.md +++ b/README.md @@ -1,11 +1,16 @@ -# Marlin 3D Printer Firmware +

MarlinFirmware's logo

-![GitHub](https://img.shields.io/github/license/marlinfirmware/marlin.svg) -![GitHub contributors](https://img.shields.io/github/contributors/marlinfirmware/marlin.svg) -![GitHub Release Date](https://img.shields.io/github/release-date/marlinfirmware/marlin.svg) -[![Build Status](https://github.com/MarlinFirmware/Marlin/workflows/CI/badge.svg?branch=bugfix-2.0.x)](https://github.com/MarlinFirmware/Marlin/actions) +

Marlin 3D Printer Firmware

- +

+ GPL-V3.0 License + Contributors + Last Release Date + CI Status + GitHub Sponsors +
+ Follow MarlinFirmware on Twitter +

Additional documentation can be found at the [Marlin Home Page](https://marlinfw.org/). Please test this firmware and let us know if it misbehaves in any way. Volunteers are standing by! @@ -20,6 +25,10 @@ This branch is for patches to the latest 2.0.x release version. Periodically thi 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](https://docs.platformio.org/en/latest/ide.html#platformio-ide). We've posted detailed instructions on [Building Marlin with Arduino](https://marlinfw.org/docs/basics/install_arduino.html) and [Building Marlin with PlatformIO for ReArm](https://marlinfw.org/docs/basics/install_rearm.html) (which applies well to other 32-bit boards). @@ -28,84 +37,29 @@ To build Marlin 2.0 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino Marlin 2.0 introduces a layer of abstraction so that all the existing high-level code can be built for 32-bit platforms while still retaining full 8-bit AVR compatibility. Retaining AVR compatibility and a single code-base is important to us, because we want to make sure that features and patches get as much testing and attention as possible, and that all platforms always benefit from the latest improvements. -### Current HALs - - #### AVR (8-bit) - - board|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Arduino AVR](https://www.arduino.cc/)|ATmega, ATTiny, etc.|16-20MHz|64-256k|2-16k|5V|no - - #### DUE - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Arduino Due](https://www.arduino.cc/en/Guide/ArduinoDue), [RAMPS-FD](https://www.reprap.org/wiki/RAMPS-FD), etc.|[SAM3X8E ARM-Cortex M3](https://www.microchip.com/wwwproducts/en/ATsam3x8e)|84MHz|512k|64+32k|3.3V|no - - #### ESP32 - - board|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [ESP32](https://www.espressif.com/en/products/hardware/esp32/overview)|Tensilica Xtensa LX6|160-240MHz variants|---|---|3.3V|--- - - #### LPC1768 / LPC1769 - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Re-ARM](https://www.kickstarter.com/projects/1245051645/re-arm-for-ramps-simple-32-bit-upgrade)|[LPC1768 ARM-Cortex M3](https://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)|100MHz|512k|32+16+16k|3.3-5V|no - [MKS SBASE](https://reprap.org/forum/read.php?13,499322)|LPC1768 ARM-Cortex M3|100MHz|512k|32+16+16k|3.3-5V|no - [Selena Compact](https://github.com/Ales2-k/Selena)|LPC1768 ARM-Cortex M3|100MHz|512k|32+16+16k|3.3-5V|no - [Azteeg X5 GT](https://www.panucatt.com/azteeg_X5_GT_reprap_3d_printer_controller_p/ax5gt.htm)|LPC1769 ARM-Cortex M3|120MHz|512k|32+16+16k|3.3-5V|no - [Smoothieboard](https://reprap.org/wiki/Smoothieboard)|LPC1769 ARM-Cortex M3|120MHz|512k|64k|3.3-5V|no - - #### SAMD51 - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Adafruit Grand Central M4](https://www.adafruit.com/product/4064)|[SAMD51P20A ARM-Cortex M4](https://www.microchip.com/wwwproducts/en/ATSAMD51P20A)|120MHz|1M|256k|3.3V|yes - - #### STM32F1 - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Arduino STM32](https://github.com/rogerclarkmelbourne/Arduino_STM32)|[STM32F1](https://www.st.com/en/microcontrollers-microprocessors/stm32f103.html) ARM-Cortex M3|72MHz|256-512k|48-64k|3.3V|no - [Geeetech3D GTM32](https://github.com/Geeetech3D/Diagram/blob/master/Rostock301/Hardware_GTM32_PRO_VB.pdf)|[STM32F1](https://www.st.com/en/microcontrollers-microprocessors/stm32f103.html) ARM-Cortex M3|72MHz|256-512k|48-64k|3.3V|no - - #### STM32F4 - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [STEVAL-3DP001V1](https://www.st.com/en/evaluation-tools/steval-3dp001v1.html)|[STM32F401VE Arm-Cortex M4](https://www.st.com/en/microcontrollers-microprocessors/stm32f401ve.html)|84MHz|512k|64+32k|3.3-5V|yes - - #### Teensy++ 2.0 - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Teensy++ 2.0](https://www.microchip.com/wwwproducts/en/AT90USB1286)|[AT90USB1286](https://www.microchip.com/wwwproducts/en/AT90USB1286)|16MHz|128k|8k|5V|no - - #### Teensy 3.1 / 3.2 - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Teensy 3.2](https://www.pjrc.com/store/teensy32.html)|[MK20DX256VLH7](https://www.mouser.com/ProductDetail/NXP-Freescale/MK20DX256VLH7) ARM-Cortex M4|72MHz|256k|32k|3.3V-5V|yes - - #### Teensy 3.5 / 3.6 - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Teensy 3.5](https://www.pjrc.com/store/teensy35.html)|[MK64FX512VMD12](https://www.mouser.com/ProductDetail/NXP-Freescale/MK64FX512VMD12) ARM-Cortex M4|120MHz|512k|192k|3.3-5V|yes - [Teensy 3.6](https://www.pjrc.com/store/teensy36.html)|[MK66FX1M0VMD18](https://www.mouser.com/ProductDetail/NXP-Freescale/MK66FX1M0VMD18) ARM-Cortex M4|180MHz|1M|256k|3.3V|yes - - #### Teensy 4.0 / 4.1 - - boards|processor|speed|flash|sram|logic|fpu - ----|---------|-----|-----|----|-----|--- - [Teensy 4.0](https://www.pjrc.com/store/teensy40.html)|[IMXRT1062DVL6A](https://www.mouser.com/new/nxp-semiconductors/nxp-imx-rt1060-crossover-processor/) ARM-Cortex M7|600MHz|1M|2M|3.3V|yes - [Teensy 4.1](https://www.pjrc.com/store/teensy41.html)|[IMXRT1062DVJ6A](https://www.mouser.com/new/nxp-semiconductors/nxp-imx-rt1060-crossover-processor/) ARM-Cortex M7|600MHz|1M|2M|3.3V|yes +### Supported Platforms + + Platform|MCU|Example Boards + --------|---|------- + [Arduino AVR](https://www.arduino.cc/)|ATmega|RAMPS, Melzi, RAMBo + [Teensy++ 2.0](https://www.microchip.com/en-us/product/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](https://www.nxp.com/products/processors-and-microcontrollers/arm-microcontrollers/general-purpose-mcus/lpc1700-cortex-m3/512-kb-flash-64-kb-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/512-kb-flash-64-kb-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 + [STM32F401](https://www.st.com/en/microcontrollers-microprocessors/stm32f401.html)|ARM® Cortex-M4|ARMED, Rumba32, SKR Pro, Lerdge, FYSETC S6, Artillery Ruby + [STM32F7x6](https://www.st.com/en/microcontrollers-microprocessors/stm32f7x6.html)|ARM® Cortex-M7|The Borg, RemRam V1 + [SAMD51P20A](https://www.adafruit.com/product/4064)|ARM® Cortex-M4|Adafruit Grand Central M4 + [Teensy 3.5](https://www.pjrc.com/store/teensy35.html)|ARM® Cortex-M4| + [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 Patches -Proposed patches should be submitted as a Pull Request against the ([bugfix-2.0.x](https://github.com/MarlinFirmware/Marlin/tree/bugfix-2.0.x)) branch. +Proposed patches should be submitted as a Pull Request against the ([bugfix-2.1.x](https://github.com/MarlinFirmware/Marlin/tree/bugfix-2.1.x)) branch. - This branch is for fixing bugs and integrating any new features for the duration of the Marlin 2.0.x life-cycle. - Follow the [Coding Standards](https://marlinfw.org/docs/development/coding_standards.html) to gain points with the maintainers. @@ -116,18 +70,35 @@ Proposed patches should be submitted as a Pull Request against the ([bugfix-2.0. - You can use `make tests-all-local` or `make tests-single-local TEST_TARGET=...`. - If you prefer Docker you can use `make tests-all-local-docker` or `make tests-all-local-docker TEST_TARGET=...`. -### [RepRap.org Wiki Page](https://reprap.org/wiki/Marlin) +## Marlin Support + +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](https://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](https://forums.reprap.org/list.php?415) +- 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 + +## 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. -## Credits +## 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](https://www.thinkyhead.com/donate-to-marlin) / Flattr: [![Flattr Scott](https://api.flattr.com/button/flattr-badge-small.png)](https://flattr.com/submit/auto?user_id=thinkyhead&url=https://github.com/MarlinFirmware/Marlin&title=Marlin&language=&tags=github&category=software) + - Scott Lahteine [[@thinkyhead](https://github.com/thinkyhead)] - USA - Project Maintainer   [💸 Donate](https://www.thinkyhead.com/donate-to-marlin) - Roxanne Neufeld [[@Roxy-3D](https://github.com/Roxy-3D)] - USA + - Keith Bennett [[@thisiskeithb](https://github.com/thisiskeithb)] - USA   [💸 Donate](https://github.com/sponsors/thisiskeithb) + - Peter Ellens [[@ellensp](https://github.com/ellensp)] - New Zealand + - 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 - - João Brazio [[@jbrazio](https://github.com/jbrazio)] - Portugal - - 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) + - Erik van der Zalm [[@ErikZalm](https://github.com/ErikZalm)] - Netherlands   [💸 Donate](https://flattr.com/submit/auto?user_id=ErikZalm&url=https://github.com/MarlinFirmware/Marlin&title=Marlin&language=&tags=github&category=software) ## License diff --git a/buildroot/bin/ci_src_filter b/buildroot/bin/ci_src_filter new file mode 100755 index 000000000000..928f492e69fa --- /dev/null +++ b/buildroot/bin/ci_src_filter @@ -0,0 +1,14 @@ +#!/usr/bin/env bash + +# exit on first failure +set -e + +SED=$(which gsed sed | head -n1) +FN="platformio.ini" + +if [[ $1 == "-n" ]]; then + "${SED}" -i "s/default_src_filter/org_src_filter/" $FN + "${SED}" -i "/org_src_filter/ s/^/default_src_filter = +\n/" $FN +else + git checkout $FN 2>/dev/null +fi diff --git a/buildroot/bin/use_example_configs b/buildroot/bin/use_example_configs index 83c0f5485d2c..cb3c2424d61f 100755 --- a/buildroot/bin/use_example_configs +++ b/buildroot/bin/use_example_configs @@ -1,8 +1,20 @@ #!/usr/bin/env bash +# +# use_example_configs [repo:]configpath +# +# Examples: +# use_example_configs Creality/CR-10/CrealityV1 +# use_example_configs release-2.0.9.4:Creality/CR-10/CrealityV1 +# +# If a configpath has spaces (or quotes) escape them or enquote the path +# + +CURR=$(git branch 2>/dev/null | grep ^* | sed 's/\* //g') +[[ $CURR == "bugfix-2.0.x" ]] && BRANCH=bugfix-2.0.x || BRANCH=bugfix-2.1.x IFS=: read -r PART1 PART2 <<< "$@" -[ -n "${PART2}" ] && { REPO="$PART1" ; RDIR="${PART2// /%20}" ; } \ - || { REPO=bugfix-2.0.x ; RDIR="${PART1// /%20}" ; } +[[ -n $PART2 ]] && { REPO="$PART1" ; UDIR="$PART2" ; } \ + || { REPO=$BRANCH ; UDIR="$PART1" ; } EXAMPLES="https://raw.githubusercontent.com/MarlinFirmware/Configurations/$REPO/config/examples" which curl >/dev/null && TOOL='curl -L -s -S -f -o wgot' @@ -12,6 +24,9 @@ restore_configs cd Marlin +RDIR="${UDIR// /%20}" +echo "Fetching $UDIR configurations from $REPO..." + $TOOL "$EXAMPLES/$RDIR/Configuration.h" >/dev/null 2>&1 && mv wgot Configuration.h $TOOL "$EXAMPLES/$RDIR/Configuration_adv.h" >/dev/null 2>&1 && mv wgot Configuration_adv.h $TOOL "$EXAMPLES/$RDIR/_Bootscreen.h" >/dev/null 2>&1 && mv wgot _Bootscreen.h diff --git a/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RC.json b/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RC.json new file mode 100644 index 000000000000..82f49fa815d6 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RC.json @@ -0,0 +1,65 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F401xx", + "f_cpu": "84000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "ldscript": "ldscript.ld", + "mcu": "stm32f401rct6", + "variant": "MARLIN_CREALITY_STM32F401RC" + }, + "debug": { + "jlink_device": "STM32F401RC", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd", + "tools": { + "stlink": { + "server": { + "arguments": [ + "-f", + "scripts/interface/stlink.cfg", + "-c", + "transport select hla_swd", + "-f", + "scripts/target/stm32f4x.cfg", + "-c", + "reset_config none" + ], + "executable": "bin/openocd", + "package": "tool-openocd" + } + } + } + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F401RC (64k RAM. 256k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 65536, + "maximum_size": 262144, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f401rc.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32H743Vx.json b/buildroot/share/PlatformIO/boards/marlin_STM32H743Vx.json new file mode 100644 index 000000000000..3b8fa73060b7 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_STM32H743Vx.json @@ -0,0 +1,61 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m7", + "extra_flags": "-DSTM32H7xx -DSTM32H743xx", + "f_cpu": "400000000L", + "mcu": "stm32h743vit6", + "product_line": "STM32H743xx", + "variant": "MARLIN_H743Vx" + }, + "connectivity": [ + "can", + "ethernet" + ], + "debug": { + "jlink_device": "STM32H743VI", + "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": "STM32H743VI (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/stm32h743vi.html", + "vendor": "ST" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_CHITU_F103.json b/buildroot/share/PlatformIO/boards/marlin_maple_CHITU_F103.json similarity index 95% rename from buildroot/share/PlatformIO/boards/marlin_CHITU_F103.json rename to buildroot/share/PlatformIO/boards/marlin_maple_CHITU_F103.json index dbfbc21cb275..45c80b3ec037 100644 --- a/buildroot/share/PlatformIO/boards/marlin_CHITU_F103.json +++ b/buildroot/share/PlatformIO/boards/marlin_maple_CHITU_F103.json @@ -15,7 +15,7 @@ ] ], "mcu": "stm32f103zet6", - "variant": "marlin_CHITU_F103" + "variant": "marlin_maple_CHITU_F103" }, "debug": { "jlink_device": "STM32F103ZE", diff --git a/buildroot/share/PlatformIO/boards/marlin_MEEB_3DP.json b/buildroot/share/PlatformIO/boards/marlin_maple_MEEB_3DP.json similarity index 96% rename from buildroot/share/PlatformIO/boards/marlin_MEEB_3DP.json rename to buildroot/share/PlatformIO/boards/marlin_maple_MEEB_3DP.json index 73ec9aaf48e2..54fd5fbed950 100644 --- a/buildroot/share/PlatformIO/boards/marlin_MEEB_3DP.json +++ b/buildroot/share/PlatformIO/boards/marlin_maple_MEEB_3DP.json @@ -18,7 +18,7 @@ "ldscript": "stm32f103xc.ld" }, "mcu": "stm32f103rct6", - "variant": "marlin_MEEB_3DP" + "variant": "marlin_maple_MEEB_3DP" }, "debug": { "jlink_device": "STM32F103RC", diff --git a/buildroot/share/PlatformIO/boards/marlin_index_mobo_rev03.json b/buildroot/share/PlatformIO/boards/marlin_opulo_lumen_rev3.json similarity index 100% rename from buildroot/share/PlatformIO/boards/marlin_index_mobo_rev03.json rename to buildroot/share/PlatformIO/boards/marlin_opulo_lumen_rev3.json diff --git a/buildroot/share/PlatformIO/debugging/launch.json b/buildroot/share/PlatformIO/debugging/launch.json index 335c4c663e89..583d860eb36c 100644 --- a/buildroot/share/PlatformIO/debugging/launch.json +++ b/buildroot/share/PlatformIO/debugging/launch.json @@ -12,26 +12,17 @@ "version": "0.2.0", "configurations": [ { - "name": "Debug STM32 (launch)", + "name": "Debug STM32 (ST-Link)", "request": "launch", "type": "cortex-debug", "servertype": "openocd", "cwd": "${workspaceRoot}", "showDevDebugOutput": false, "configFiles": [ "interface/stlink.cfg", "target/stm32f4x.cfg" ], - "device": "STM32F407", - "executable": ".pio/build/BIGTREE_SKR_2_USB_debug/firmware.elf", - }, - { - "name": "Debug STM32 (attach)", - "request": "attach", - "type": "cortex-debug", - "servertype": "openocd", - "cwd": "${workspaceRoot}", - "showDevDebugOutput": false, - "configFiles": [ "interface/stlink.cfg", "target/stm32f4x.cfg" ], - "device": "STM32F407", - "executable": ".pio/build/BIGTREE_SKR_2_USB_debug/firmware.elf", + "device": "stlink", + "executable": "${workspaceRoot}/.pio/build/BIGTREE_SKR_2_USB_debug/firmware.elf", + "openOCDLaunchCommands": [ "init", "reset init" ], + "svdFile": "${env:HOME}/.platformio/platforms/ststm32@12.1.1/misc/svd/STM32F40x.svd", }, { "name": "Debug Sim", diff --git a/buildroot/share/PlatformIO/ldscripts/fysetc_stm32f103rc.ld b/buildroot/share/PlatformIO/ldscripts/crealityPro.ld similarity index 50% rename from buildroot/share/PlatformIO/ldscripts/fysetc_stm32f103rc.ld rename to buildroot/share/PlatformIO/ldscripts/crealityPro.ld index 6777e5918262..442c5c75078f 100644 --- a/buildroot/share/PlatformIO/ldscripts/fysetc_stm32f103rc.ld +++ b/buildroot/share/PlatformIO/ldscripts/crealityPro.ld @@ -1,11 +1,7 @@ -/* - * Linker script for Generic STM32F103RC boards, using the generic bootloader (which takes the lower 8k of memory) - */ - MEMORY { - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - rom (rx) : ORIGIN = 0x08008000, LENGTH = 256K - 32K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K - 40 + rom (rx) : ORIGIN = 0x08010000, LENGTH = 512K - 64K } /* Provide memory region aliases for common.inc */ @@ -15,4 +11,4 @@ REGION_ALIAS("REGION_BSS", ram); REGION_ALIAS("REGION_RODATA", rom); /* Let common.inc handle the real work. */ -INCLUDE common.inc +INCLUDE common.inc \ No newline at end of file diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py index eccee7606804..551f4c63160b 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py @@ -4,29 +4,9 @@ import pioutil if pioutil.is_pio_build(): - try: - import configparser - except ImportError: - import ConfigParser as configparser - import os Import("env", "projenv") - config = configparser.ConfigParser() - config.read("platformio.ini") - - # - # Upload actions - # - def before_upload(source, target, env): - env.Execute("pwd") - - def after_upload(source, target, env): - env.Execute("pwd") - - env.AddPreAction("upload", before_upload) - env.AddPostAction("upload", after_upload) - flash_size = 0 vect_tab_addr = 0 @@ -38,6 +18,3 @@ 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)) - - import marlin - marlin.custom_ld_script("STM32F103RC_MEEB_3DP.ld") diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.h b/buildroot/share/PlatformIO/scripts/common-dependencies.h index 4aa97c41ad69..da2d380a82b6 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.h +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.h @@ -53,7 +53,7 @@ #if ENABLED(BACKLASH_GCODE) #define HAS_MENU_BACKLASH #endif - #if ENABLED(LEVEL_BED_CORNERS) + #if ENABLED(LCD_BED_TRAMMING) #define HAS_MENU_BED_CORNERS #endif #if ENABLED(CANCEL_OBJECTS) diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.py b/buildroot/share/PlatformIO/scripts/common-dependencies.py index 24e780d9b670..e9e8c7918767 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.py +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.py @@ -15,7 +15,7 @@ FEATURE_CONFIG = {} def validate_pio(): - PIO_VERSION_MIN = (5, 0, 3) + PIO_VERSION_MIN = (6, 0, 1) try: from platformio import VERSION as PIO_VERSION weights = (1000, 100, 1) @@ -174,7 +174,7 @@ def apply_features_config(): env.SConscript(feat['extra_scripts'], exports="env") if 'src_filter' in feat: - blab("========== Adding src_filter for %s... " % feature, 2) + blab("========== Adding build_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']) @@ -184,7 +184,7 @@ def apply_features_config(): src_filter = re.sub(r'[+-]' + d, '', src_filter) src_filter = feat['src_filter'] + ' ' + src_filter - set_env_field('src_filter', [src_filter]) + set_env_field('build_src_filter', [src_filter]) env.Replace(SRC_FILTER=src_filter) if 'lib_ignore' in feat: diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index d572873ad764..1bd77812f71c 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -21,6 +21,10 @@ from platformio.package.meta import PackageSpec platform_packages = env.GetProjectOption('platform_packages') + + # Remove all tool items from platform_packages + platform_packages = [x for x in platform_packages if not x.startswith("platformio/tool-")] + if len(platform_packages) == 0: framewords = { "Ststm32Platform": "framework-arduinoststm32", diff --git a/buildroot/share/PlatformIO/scripts/lerdge.py b/buildroot/share/PlatformIO/scripts/lerdge.py index 505a935560a9..06e454393073 100644 --- a/buildroot/share/PlatformIO/scripts/lerdge.py +++ b/buildroot/share/PlatformIO/scripts/lerdge.py @@ -26,10 +26,10 @@ def encrypt_file(input, output_file, file_length): input_file[i] = encryptByte(input_file[i]) output_file.write(input_file) - # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt + # Encrypt ${PROGNAME}.bin and save it with the name given in build.crypt_lerdge def encrypt(source, target, env): fwpath = target[0].path - enname = board.get("build.encrypt") + enname = board.get("build.crypt_lerdge") print("Encrypting %s to %s" % (fwpath, enname)) fwfile = open(fwpath, "rb") enfile = open(target[0].dir.path + "/" + enname, "wb") @@ -41,9 +41,9 @@ def encrypt(source, target, env): enfile.close() os.remove(fwpath) - if 'encrypt' in board.get("build").keys(): - if board.get("build.encrypt") != "": + if 'crypt_lerdge' in board.get("build").keys(): + if board.get("build.crypt_lerdge") != "": marlin.add_post_action(encrypt) else: - print("LERDGE builds require output file via board_build.encrypt = 'filename' parameter") + print("LERDGE builds require output file via board_build.crypt_lerdge = 'filename' parameter") exit(1) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index 8ac36b7d59b5..580268c42324 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -41,8 +41,8 @@ def custom_ld_script(ldname): 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 +# Encrypt ${PROGNAME}.bin and save it with a new name. This applies (mostly) to MKS boards +# This PostAction is set up by offset_and_rename.py for envs with 'build.encrypt_mks'. def encrypt_mks(source, target, env, new_name): import sys diff --git a/buildroot/share/PlatformIO/scripts/mks_robin.py b/buildroot/share/PlatformIO/scripts/mks_robin.py deleted file mode 100644 index 7b423bedabc7..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# 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 deleted file mode 100644 index 645230c625c2..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin_e3.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# 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 deleted file mode 100644 index bb15cb5a70f2..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# 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 deleted file mode 100644 index 123b043f7cfb..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin_lite.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# 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 deleted file mode 100644 index 092231eae81f..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# 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 deleted file mode 100644 index d1d175dd1c17..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# 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 deleted file mode 100644 index 32d1af23662c..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# 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 deleted file mode 100644 index 7e635bd6ecf7..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# 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 deleted file mode 100644 index 54526aeaef57..000000000000 --- a/buildroot/share/PlatformIO/scripts/mks_robin_pro.py +++ /dev/null @@ -1,5 +0,0 @@ -# -# mks_robin_pro.py -# -import robin -robin.prepare("0x08007000", "mks_robin_pro.ld", "Robin_pro.bin") diff --git a/buildroot/share/PlatformIO/scripts/offset_and_rename.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py index ddbb786fecd1..6f445246190f 100644 --- a/buildroot/share/PlatformIO/scripts/offset_and_rename.py +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -39,15 +39,15 @@ env["LINKFLAGS"][i] = "-Wl,--defsym=LD_MAX_DATA_SIZE=" + str(maximum_ram_size - 40) # - # For build.encrypt rename and encode the firmware file. + # For build.encrypt_mks rename and encode the firmware file. # - if 'encrypt' in board_keys: + if 'encrypt_mks' in board_keys: - # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt + # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt_mks def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) + marlin.encrypt_mks(source, target, env, board.get("build.encrypt_mks")) - if board.get("build.encrypt") != "": + if board.get("build.encrypt_mks") != "": marlin.add_post_action(encrypt) # diff --git a/buildroot/share/PlatformIO/scripts/openblt.py b/buildroot/share/PlatformIO/scripts/openblt.py index 61b38a5e87f7..33e82898f7b4 100644 --- a/buildroot/share/PlatformIO/scripts/openblt.py +++ b/buildroot/share/PlatformIO/scripts/openblt.py @@ -10,11 +10,11 @@ board = env.BoardConfig() board_keys = board.get("build").keys() - if 'encrypt' in board_keys: + if 'encode' 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") + "\"$BUILD_DIR/${PROGNAME}.elf\"", "\"" + join("$BUILD_DIR", board.get("build.encode")) + "\"" + ]), "Building " + board.get("build.encode")) ) diff --git a/buildroot/share/PlatformIO/scripts/preprocessor.py b/buildroot/share/PlatformIO/scripts/preprocessor.py index 6f4ed900cab1..d9c472006c28 100644 --- a/buildroot/share/PlatformIO/scripts/preprocessor.py +++ b/buildroot/share/PlatformIO/scripts/preprocessor.py @@ -3,6 +3,7 @@ # import subprocess,os,re +nocache = 1 verbose = 0 def blab(str): @@ -50,7 +51,7 @@ def run_preprocessor(env, fn=None): # def search_compiler(env): - ENV_BUILD_PATH = os.path.join(env.Dictionary('PROJECT_BUILD_DIR'), env['PIOENV']) + ENV_BUILD_PATH = os.path.join(env['PROJECT_BUILD_DIR'], env['PIOENV']) GCC_PATH_CACHE = os.path.join(ENV_BUILD_PATH, ".gcc_path") try: @@ -60,7 +61,8 @@ def search_compiler(env): except: pass - if os.path.exists(GCC_PATH_CACHE): + # Warning: The cached .gcc_path will obscure a newly-installed toolkit + if not nocache and os.path.exists(GCC_PATH_CACHE): blab("Getting g++ path from cache") with open(GCC_PATH_CACHE, 'r') as f: return f.read() @@ -87,7 +89,7 @@ def search_compiler(env): # 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): + if not nocache and os.path.exists(ENV_BUILD_PATH): blab("Caching g++ for current env") with open(GCC_PATH_CACHE, 'w+') as f: f.write(filepath) diff --git a/buildroot/share/PlatformIO/scripts/robin.py b/buildroot/share/PlatformIO/scripts/robin.py deleted file mode 100644 index ffc9a43b9004..000000000000 --- a/buildroot/share/PlatformIO/scripts/robin.py +++ /dev/null @@ -1,14 +0,0 @@ -# -# robin.py -# - -# Apply customizations for a MKS Robin -def prepare(address, ldname, fwname): - import pioutil - if pioutil.is_pio_build(): - import marlin - def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, fwname) - marlin.relocate_firmware(address) - marlin.custom_ld_script(ldname) - marlin.add_post_action(encrypt); diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PeripheralPins.c new file mode 100644 index 000000000000..418ef5aa7abc --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PeripheralPins.c @@ -0,0 +1,252 @@ +/* + ******************************************************************************* + * Copyright (c) 2019, STMicroelectronics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************* + * Automatically generated from STM32F401R[(B-C)|(D-E)]Tx.xml + */ +#include "Arduino.h" +#include "PeripheralPins.h" + +/* ===== + * Note: Commented lines are alternative possibilities which are not used per default. + * If you change them, you will have to know what you do + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +WEAK const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + {NC, NP, 0} +}; +#endif + +//*** No DAC *** + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C2)}, + {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C3)}, + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_I2C_SCL[] = { + {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +WEAK const PinMap PinMap_PWM[] = { + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 + {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_11, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RX[] = { + {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RTS[] = { + {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_CTS[] = { + {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + //{PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {NC, NP, 0} +}; +#endif + +//*** No CAN *** + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB_OTG_FS[] = { +#ifndef ARDUINO_CoreBoard_F401RC + {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS + {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID +#endif + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; +#endif + +//*** No USB_OTG_HS *** + +//*** SD *** + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4 + {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5 + {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6 + {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PinNamesVar.h new file mode 100644 index 000000000000..e1536bcf30f4 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/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_CREALITY_STM32F401RC/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/hal_conf_custom.h new file mode 100644 index 000000000000..1dd047bb9005 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/hal_conf_custom.h @@ -0,0 +1,495 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_conf.h + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + *

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

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_CONF_CUSTOM +#define __STM32F4xx_HAL_CONF_CUSTOM + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ + /** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_IWDG_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_RTC_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_PCD_MODULE_ENABLED // Automatically added if any type of USB is enabled, as in Arduino IDE. (STM32 v3.10700.191028) + +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRYP_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_DCMI_MODULE_ENABLED +//#define HAL_DMA2D_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED +//#define HAL_NAND_MODULE_ENABLED +//#define HAL_NOR_MODULE_ENABLED +//#define HAL_PCCARD_MODULE_ENABLED +//#define HAL_SRAM_MODULE_ENABLED +//#define HAL_SDRAM_MODULE_ENABLED +//#define HAL_HASH_MODULE_ENABLED +//#define HAL_EXTI_MODULE_ENABLED +//#define HAL_SMBUS_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_LTDC_MODULE_ENABLED +//#define HAL_DSI_MODULE_ENABLED +//#define HAL_QSPI_MODULE_ENABLED +//#define HAL_RNG_MODULE_ENABLED +//#define HAL_SAI_MODULE_ENABLED +#define HAL_SD_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED +//#define HAL_USART_MODULE_ENABLED +//#define HAL_IRDA_MODULE_ENABLED +//#define HAL_SMARTCARD_MODULE_ENABLED +//#define HAL_WWDG_MODULE_ENABLED +//#define HAL_HCD_MODULE_ENABLED +//#define HAL_FMPI2C_MODULE_ENABLED +//#define HAL_SPDIFRX_MODULE_ENABLED +//#define HAL_DFSDM_MODULE_ENABLED +//#define HAL_LPTIM_MODULE_ENABLED +//#define HAL_MMC_MODULE_ENABLED + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#ifndef HSE_VALUE +#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#ifndef HSE_STARTUP_TIMEOUT +#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#ifndef HSI_VALUE +#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#ifndef LSI_VALUE +#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz +The real value may vary depending on the variations +in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + */ +#ifndef LSE_VALUE +#define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#ifndef LSE_STARTUP_TIMEOUT +#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#ifndef EXTERNAL_CLOCK_VALUE +#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#if !defined (VDD_VALUE) +#define VDD_VALUE 3300U /*!< Value of VDD in mv */ +#endif +#if !defined (TICK_INT_PRIORITY) +#define TICK_INT_PRIORITY 0x00U /*!< tick interrupt priority */ +#endif +#if !defined (USE_RTOS) +#define USE_RTOS 0U +#endif +#if !defined (PREFETCH_ENABLE) +#define PREFETCH_ENABLE 1U +#endif +#if !defined (INSTRUCTION_CACHE_ENABLE) +#define INSTRUCTION_CACHE_ENABLE 1U +#endif +#if !defined (DATA_CACHE_ENABLE) +#define DATA_CACHE_ENABLE 1U +#endif + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1U */ + +/* ################## Ethernet peripheral configuration ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ + +/* DP83848_PHY_ADDRESS Address*/ +#define DP83848_PHY_ADDRESS 0x01U +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY 0x000000FFU +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY 0x00000FFFU + +#define PHY_READ_TO 0x0000FFFFU +#define PHY_WRITE_TO 0x0000FFFFU + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ +#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */ + +#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver + * Activated: CRC code is present inside driver + * Deactivated: CRC code cleaned from driver + */ +#ifndef USE_SPI_CRC +#define USE_SPI_CRC 0U +#endif + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED +#include "stm32f4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED +#include "stm32f4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED +#include "stm32f4xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED +#include "stm32f4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED +#include "stm32f4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED +#include "stm32f4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED +#include "stm32f4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED +#include "stm32f4xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED +#include "stm32f4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED +#include "stm32f4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED +#include "stm32f4xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED +#include "stm32f4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED +#include "stm32f4xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED +#include "stm32f4xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED +#include "stm32f4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED +#include "stm32f4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED +#include "stm32f4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED +#include "stm32f4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED +#include "stm32f4xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED +#include "stm32f4xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED +#include "stm32f4xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED +#include "stm32f4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED +#include "stm32f4xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED +#include "stm32f4xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED +#include "stm32f4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED +#include "stm32f4xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED +#include "stm32f4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED +#include "stm32f4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED +#include "stm32f4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED +#include "stm32f4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED +#include "stm32f4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED +#include "stm32f4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED +#include "stm32f4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED +#include "stm32f4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED +#include "stm32f4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED +#include "stm32f4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED +#include "stm32f4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED +#include "stm32f4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED +#include "stm32f4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED +#include "stm32f4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED +#include "stm32f4xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED +#include "stm32f4xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED +#include "stm32f4xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_FMPI2C_MODULE_ENABLED +#include "stm32f4xx_hal_fmpi2c.h" +#endif /* HAL_FMPI2C_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED +#include "stm32f4xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED +#include "stm32f4xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32f4xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED +#include "stm32f4xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ +#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ +void assert_failed(uint8_t *file, uint32_t line); +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_CONF_CUSTOM_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/ldscript.ld new file mode 100644 index 000000000000..004714cd6dc0 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/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 = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text ALIGN(4): + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.cpp new file mode 100644 index 000000000000..71f3509ed57b --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/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_CREALITY_STM32F401RC/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.h new file mode 100644 index 000000000000..b5a4e5ef80c2 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/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 0 // | 0 | A0 | | | | | +#define PA1 1 // | 1 | A1 | | | | | +#define PA2 2 // | 2 | A2 | USART2_TX | | | | +#define PA3 3 // | 3 | A3 | USART2_RX | | | | +#define PA4 4 // | 4 | A4 | | | SPI1_SS, (SPI3_SS) | | +#define PA5 5 // | 5 | A5 | | | SPI1_SCK | | +#define PA6 6 // | 6 | A6 | | | SPI1_MISO | | +#define PA7 7 // | 7 | A7 | | | SPI1_MOSI | | +#define PA8 8 // | 8 | | | TWI3_SCL | | | +#define PA9 9 // | 9 | | USART1_TX | | | | +#define PA10 10 // | 10 | | USART1_RX | | | | +#define PA11 11 // | 11 | | USART6_TX | | | | +#define PA12 12 // | 12 | | USART6_RX | | | | +#define PA13 13 // | 13 | | | | | SWD_SWDIO | +#define PA14 14 // | 14 | | | | | SWD_SWCLK | +#define PA15 15 // | 15 | | | | SPI3_SS, (SPI1_SS) | | +// |---------|--------|-----------|----------|------------------------|-----------| +#define PB0 16 // | 16 | A8 | | | | | +#define PB1 17 // | 17 | A9 | | | | | +#define PB2 18 // | 18 | | | | | BOOT1 | +#define PB3 19 // | 19 | | | TWI2_SDA | SPI3_SCK, (SPI1_SCK) | | +#define PB4 20 // | 20 | | | TWI3_SDA | SPI3_MISO, (SPI1_MISO) | | +#define PB5 21 // | 21 | | | | SPI3_MOSI, (SPI1_MOSI) | | +#define PB6 22 // | 22 | | USART1_TX | TWI1_SCL | | | +#define PB7 23 // | 23 | | USART1_RX | TWI1_SDA | | | +#define PB8 24 // | 24 | | | TWI1_SCL | | | +#define PB9 25 // | 25 | | | TWI1_SDA | SPI2_SS | | +#define PB10 26 // | 26 | | | TWI2_SCL | SPI2_SCK | | +#define PB12 27 // | 27 | | | | SPI2_SS | | +#define PB13 28 // | 28 | | | | SPI2_SCK | | +#define PB14 29 // | 29 | | | | SPI2_MISO | | +#define PB15 30 // | 30 | | | | SPI2_MOSI | | +// |---------|--------|-----------|----------|------------------------|-----------| +#define PC0 31 // | 31 | A10 | | | | | +#define PC1 32 // | 32 | A11 | | | | | +#define PC2 33 // | 33 | A12 | | | SPI2_MISO | | +#define PC3 34 // | 34 | A13 | | | SPI2_MOSI | | +#define PC4 35 // | 35 | A14 | | | | | +#define PC5 36 // | 36 | A15 | | | | | +#define PC6 37 // | 37 | | USART6_TX | | | | +#define PC7 38 // | 38 | | USART6_RX | | | | +#define PC8 39 // | 39 | | | | | | +#define PC9 40 // | 40 | | | TWI3_SDA | | | +#define PC10 41 // | 41 | | | | SPI3_SCK | | +#define PC11 42 // | 42 | | | | SPI3_MISO | | +#define PC12 43 // | 43 | | | | SPI3_MOSI | | +#define PC13 44 // | 44 | | | | | | +#define PC14 45 // | 45 | | | | | OSC32_IN | +#define PC15 46 // | 46 | | | | | OSC32_OUT | +// |---------|--------|-----------|----------|------------------------|-----------| +#define PD2 47 // | 47 | | | | | | +// |---------|--------|-----------|----------|------------------------|-----------| +#define PH0 48 // | 48 | | | | | OSC_IN | +#define PH1 49 // | 49 | | | | | OSC_OUT | +// |---------|--------|-----------|----------|------------------------|-----------| + +// This must be a literal +#define NUM_DIGITAL_PINS 50 +#define NUM_ANALOG_INPUTS 16 + +// SPI definitions +#define PIN_SPI_SS PA4 +#define PIN_SPI_SS1 PA4 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + + +// Timer Definitions +#define TIMER_TONE TIM2 +#define TIMER_SERVO 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 instanciate a hardware Serial using its peripheral name. +// Example: HardwareSerial mySerial(USART3); +// will use PIN_SERIAL3_RX and PIN_SERIAL3_TX if defined. +#define PIN_SERIAL1_RX PA10 +#define PIN_SERIAL1_TX PA9 +#define PIN_SERIAL2_RX PA3 +#define PIN_SERIAL2_TX PA2 + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus + // These serial port names are intended to allow libraries and architecture-neutral + // sketches to automatically default to the correct port name for a particular type + // of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, + // the first hardware serial port whose RX/TX pins are not dedicated to another use. + // + // SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor + // + // SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial + // + // SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library + // + // SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. + // + // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX + // pins are NOT connected to anything by default. + #define SERIAL_PORT_MONITOR Serial + #define SERIAL_PORT_HARDWARE Serial1 + #define SERIAL_PORT_HARDWARE_OPEN Serial2 +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PeripheralPins.c new file mode 100644 index 000000000000..49c4cbb87aa9 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PeripheralPins.c @@ -0,0 +1,539 @@ +/* + ******************************************************************************* + * Copyright (c) 2020-2021, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + */ +/* + * Automatically generated from STM32H742V(G-I)Hx.xml, STM32H742V(G-I)Tx.xml + * STM32H743V(G-I)Hx.xml, STM32H743VGTx.xml + * STM32H743VITx.xml, STM32H750VBTx.xml + * STM32H753VIHx.xml, STM32H753VITx.xml + * CubeMX DB release 6.0.30 + */ +#if !defined(CUSTOM_PERIPHERAL_PINS) +#include "Arduino.h" +#include "PeripheralPins.h" + +/* ===== + * Notes: + * - The pins mentioned Px_y_ALTz are alternative possibilities which use other + * HW peripheral instances. You can use them the same way as any other "normal" + * pin (i.e. analogWrite(PA7_ALT1, 128);). + * + * - Commented lines are alternative possibilities which are not used per default. + * If you change them, you will have to know what you do + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +WEAK const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC1_INP16 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 17, 0)}, // ADC1_INP17 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_INP14 + {PA_2_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_INP14 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_INP15 + {PA_3_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_INP15 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 18, 0)}, // ADC1_INP18 + {PA_4_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 18, 0)}, // ADC2_INP18 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 19, 0)}, // ADC1_INP19 + {PA_5_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 19, 0)}, // ADC2_INP19 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_INP3 + {PA_6_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_INP3 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_INP7 + {PA_7_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_INP7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_INP9 + {PB_0_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_INP9 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_INP5 + {PB_1_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_INP5 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_INP10 + {PC_0_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_INP10 + {PC_0_ALT2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_INP10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_INP11 + {PC_1_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_INP11 + {PC_1_ALT2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_INP11 + {PC_2_C, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_INP0 + {PC_3_C, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_INP1 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_INP4 + {PC_4_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_INP4 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_INP8 + {PC_5_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_INP8 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC1_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC1_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_7_ALT1, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_9_ALT1, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {PD_13, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SCL[] = { + {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_6_ALT1, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_8_ALT1, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PD_12, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)}, + {NC, NP, 0} +}; +#endif + +//*** TIM *** + +#ifdef HAL_TIM_MODULE_ENABLED +WEAK const PinMap PinMap_TIM[] = { + {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_0_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PA_1_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + {PA_1_ALT2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PA_2_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + {PA_2_ALT2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 0)}, // TIM15_CH1 + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + {PA_3_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + {PA_3_ALT2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 2, 0)}, // TIM15_CH2 + {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_5_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PA_6_ALT1, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PA_7_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PA_7_ALT2, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + {PA_7_ALT3, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_0_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PB_0_ALT2, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PB_1_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PB_1_ALT2, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PB_6_ALT1, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 1)}, // TIM16_CH1N + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PB_7_ALT1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 1)}, // TIM17_CH1N + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PB_8_ALT1, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 0)}, // TIM16_CH1 + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PB_9_ALT1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 0)}, // TIM17_CH1 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_14_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + {PB_14_ALT2, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM12, 1, 0)}, // TIM12_CH1 + {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PB_15_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + {PB_15_ALT2, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM12, 2, 0)}, // TIM12_CH2 + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PC_6_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PC_7_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PC_8_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PC_9_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PE_4, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N + {PE_5, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 0)}, // TIM15_CH1 + {PE_6, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 2, 0)}, // TIM15_CH2 + {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {NC, NP, 0} +}; +#endif + +//*** UART *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, + {PA_9_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_12, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_UART4)}, + {PA_15, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + {PB_4, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + {PB_6, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_LPUART)}, + {PB_6_ALT1, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + {PB_6_ALT2, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_9, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PB_13, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + {PB_14, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_10_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PE_1, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RX[] = { + {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + {PA_10, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, + {PA_10_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_UART4)}, + {PB_3, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + {PB_5, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + {PB_7, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_LPUART)}, + {PB_7_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_8, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PB_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + {PB_15, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_11_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {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)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RTS[] = { + {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_12, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, + {PA_12_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_14, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_14_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_15, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_9, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_CTS[] = { + {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_11, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, + {PA_11_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PB_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_14, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_10, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_7_ALT1, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_5_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + {PB_5_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_3_C, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PD_6, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, + {PD_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PE_6, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {PE_14, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_6_ALT1, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_4_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_2_C, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PE_5, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {PE_13, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_5_ALT1, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_3_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_3_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {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_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PA_4_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PA_11, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_15_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PA_15_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI6)}, + {PB_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PE_4, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {PE_11, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +//*** FDCAN *** + +#ifdef HAL_FDCAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + {PA_11, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_5, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PB_8, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_12, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PD_0, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_FDCAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_TD[] = { + {PA_12, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_6, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PB_9, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_13, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PD_1, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {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 + {PA_1_ALT1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_CLK + {PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO + {PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL + {PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV + {PA_7_ALT1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_DV + {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_C, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2 + {PC_3_C, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK + {PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0 + {PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1 + {PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + {NC, NP, 0} +}; +#endif + +//*** 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_QUADSPI)}, // QUADSPI_BK1_IO0 + {PD_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO0 + {PE_7, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK2_IO0 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_QSPI_MODULE_ENABLED +WEAK const PinMap PinMap_QUADSPI_DATA1[] = { + {PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO1 + {PD_12, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO1 + {PE_8, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK2_IO1 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_QSPI_MODULE_ENABLED +WEAK const PinMap PinMap_QUADSPI_DATA2[] = { + {PE_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO2 + {PE_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK2_IO2 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_QSPI_MODULE_ENABLED +WEAK const PinMap PinMap_QUADSPI_DATA3[] = { + {PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO3 + {PD_13, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO3 + {PE_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK2_IO3 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_QSPI_MODULE_ENABLED +WEAK const PinMap PinMap_QUADSPI_SCLK[] = { + {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_CLK + {NC, NP, 0} +}; +#endif + +#ifdef HAL_QSPI_MODULE_ENABLED +WEAK const PinMap PinMap_QUADSPI_SSEL[] = { + {PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK1_NCS + {PB_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_NCS + {PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK2_NCS + {NC, NP, 0} +}; +#endif + +//*** USB *** + +#if defined(HAL_PCD_MODULE_ENABLED) || defined(HAL_HCD_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} +}; +#endif + +#if defined(HAL_PCD_MODULE_ENABLED) || defined(HAL_HCD_MODULE_ENABLED) +WEAK const PinMap PinMap_USB_OTG_HS[] = { +#ifdef USE_USB_HS_IN_FS + // {PA_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 + {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 + {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_C, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3_C, 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 + +//*** SD *** + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + {PA_0, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_SDIO2)}, // SDMMC2_CMD + {PB_3, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SDIO2)}, // SDMMC2_D2 + {PB_4, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SDIO2)}, // SDMMC2_D3 + {PB_8, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF7_SDIO1)}, // SDMMC1_CKIN + {PB_8_ALT1, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO1)}, // SDMMC1_D4 + {PB_8_ALT2, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_SDIO2)}, // SDMMC2_D4 + {PB_9, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF7_SDIO1)}, // SDMMC1_CDIR + {PB_9_ALT1, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO1)}, // SDMMC1_D5 + {PB_9_ALT2, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_SDIO2)}, // SDMMC2_D5 + {PB_14, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SDIO2)}, // SDMMC2_D0 + {PB_15, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SDIO2)}, // SDMMC2_D1 + {PC_1, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_SDIO2)}, // SDMMC2_CK + {PC_6, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF8_SDIO1)}, // SDMMC1_D0DIR + {PC_6_ALT1, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO1)}, // SDMMC1_D6 + {PC_6_ALT2, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_SDIO2)}, // SDMMC2_D6 + {PC_7, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF8_SDIO1)}, // SDMMC1_D123DIR + {PC_7_ALT1, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO1)}, // SDMMC1_D7 + {PC_7_ALT2, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_SDIO2)}, // SDMMC2_D7 + {PC_8, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO1)}, // SDMMC1_D0 + {PC_9, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO1)}, // SDMMC1_D1 + {PC_10, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO1)}, // SDMMC1_D2 + {PC_11, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO1)}, // SDMMC1_D3 + {PC_12, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO1)}, // SDMMC1_CK + {PD_2, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO1)}, // SDMMC1_CMD + {PD_6, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF11_SDIO2)}, // SDMMC2_CK + {PD_7, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF11_SDIO2)}, // SDMMC2_CMD + {NC, NP, 0} +}; +#endif + +#endif /* !CUSTOM_PERIPHERAL_PINS */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PinNamesVar.h new file mode 100644 index 000000000000..2128732a400c --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PinNamesVar.h @@ -0,0 +1,112 @@ +/* Dual pad pin name */ +PC_2_C = PC_2 | PDUAL, +PC_3_C = PC_3 | PDUAL, + +/* Alternate pin name */ +PA_0_ALT1 = PA_0 | ALT1, +PA_1_ALT1 = PA_1 | ALT1, +PA_1_ALT2 = PA_1 | ALT2, +PA_2_ALT1 = PA_2 | ALT1, +PA_2_ALT2 = PA_2 | ALT2, +PA_3_ALT1 = PA_3 | ALT1, +PA_3_ALT2 = PA_3 | ALT2, +PA_4_ALT1 = PA_4 | ALT1, +PA_4_ALT2 = PA_4 | ALT2, +PA_5_ALT1 = PA_5 | ALT1, +PA_6_ALT1 = PA_6 | ALT1, +PA_7_ALT1 = PA_7 | ALT1, +PA_7_ALT2 = PA_7 | ALT2, +PA_7_ALT3 = PA_7 | ALT3, +PA_9_ALT1 = PA_9 | ALT1, +PA_10_ALT1 = PA_10 | ALT1, +PA_11_ALT1 = PA_11 | ALT1, +PA_12_ALT1 = PA_12 | ALT1, +PA_15_ALT1 = PA_15 | ALT1, +PA_15_ALT2 = PA_15 | ALT2, +PB_0_ALT1 = PB_0 | ALT1, +PB_0_ALT2 = PB_0 | ALT2, +PB_1_ALT1 = PB_1 | ALT1, +PB_1_ALT2 = PB_1 | ALT2, +PB_3_ALT1 = PB_3 | ALT1, +PB_3_ALT2 = PB_3 | ALT2, +PB_4_ALT1 = PB_4 | ALT1, +PB_4_ALT2 = PB_4 | ALT2, +PB_5_ALT1 = PB_5 | ALT1, +PB_5_ALT2 = PB_5 | ALT2, +PB_6_ALT1 = PB_6 | ALT1, +PB_6_ALT2 = PB_6 | ALT2, +PB_7_ALT1 = PB_7 | ALT1, +PB_8_ALT1 = PB_8 | ALT1, +PB_8_ALT2 = PB_8 | ALT2, +PB_9_ALT1 = PB_9 | ALT1, +PB_9_ALT2 = PB_9 | ALT2, +PB_14_ALT1 = PB_14 | ALT1, +PB_14_ALT2 = PB_14 | ALT2, +PB_15_ALT1 = PB_15 | ALT1, +PB_15_ALT2 = PB_15 | ALT2, +PC_0_ALT1 = PC_0 | ALT1, +PC_0_ALT2 = PC_0 | ALT2, +PC_1_ALT1 = PC_1 | ALT1, +PC_1_ALT2 = PC_1 | ALT2, +PC_4_ALT1 = PC_4 | ALT1, +PC_5_ALT1 = PC_5 | ALT1, +PC_6_ALT1 = PC_6 | ALT1, +PC_6_ALT2 = PC_6 | ALT2, +PC_7_ALT1 = PC_7 | ALT1, +PC_7_ALT2 = PC_7 | ALT2, +PC_8_ALT1 = PC_8 | ALT1, +PC_9_ALT1 = PC_9 | ALT1, +PC_10_ALT1 = PC_10 | ALT1, +PC_11_ALT1 = PC_11 | ALT1, + +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, /* 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 = NC, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = NC, +#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_DM = PA_11, + USB_OTG_FS_DP = PA_12, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_DIR = PC_2_C, + USB_OTG_HS_ULPI_NXT = PC_3_C, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_VBUS = PB_13, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/ldscript.ld new file mode 100644 index 000000000000..7d248a268283 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/ldscript.ld @@ -0,0 +1,208 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Author : Auto-generated by STM32CubeIDE +** +** Abstract : Linker script for STM32H743VI 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 = 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_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_H743Vx/variant_MARLIN_STM32H743VX.cpp b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.cpp new file mode 100644 index 000000000000..7813f8860e58 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.cpp @@ -0,0 +1,245 @@ +/* + ******************************************************************************* + * Copyright (c) 2020-2021, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + */ +#if defined(STM32H743xx) +#include "pins_arduino.h" + +// Digital PinName array +const PinName digitalPin[] = { + PA_0, // D0/A0 + PA_1, // D1/A1 + PA_2, // D2/A2 + PA_3, // D3/A3 + PA_4, // D4/A4 + PA_5, // D5/A5 + PA_6, // D6/A6 + PA_7, // D7/A7 + PA_8, // D8 + PA_9, // D9 + PA_10, // D10 + PA_11, // D11 + PA_12, // D12 + PA_13, // D13 + PA_14, // D14 + PA_15, // D15 + PB_0, // D16/A8 + PB_1, // D17/A9 + PB_2, // D18 + PB_3, // D19 + PB_4, // D20 + PB_5, // D21 + PB_6, // D22 + PB_7, // D23 + PB_8, // D24 + PB_9, // D25 + PB_10, // D26 + PB_11, // D27 + PB_12, // D28 + PB_13, // D29 + PB_14, // D30 + PB_15, // D31 + PC_0, // D32/A10 + PC_1, // D33/A11 + PC_4, // D34/A12 + PC_5, // D35/A13 + PC_6, // D36 + PC_7, // D37 + PC_8, // D38 + PC_9, // D39 + PC_10, // D40 + PC_11, // D41 + PC_12, // D42 + PC_13, // D43 + PC_14, // D44 + PC_15, // D45 + PD_0, // D46 + PD_1, // D47 + PD_2, // D48 + PD_3, // D49 + PD_4, // D50 + PD_5, // D51 + PD_6, // D52 + PD_7, // D53 + PD_8, // D54 + PD_9, // D55 + PD_10, // D56 + PD_11, // D57 + PD_12, // D58 + PD_13, // D59 + PD_14, // D60 + PD_15, // D61 + PE_0, // D62 + PE_1, // D63 + PE_2, // D64 + PE_3, // D65 + PE_4, // D66 + PE_5, // D67 + PE_6, // D68 + PE_7, // D69 + PE_8, // D70 + PE_9, // D71 + PE_10, // D72 + PE_11, // D73 + PE_12, // D74 + PE_13, // D75 + PE_14, // D76 + PE_15, // D77 + PH_0, // D78 + PH_1, // D79 + PC_2_C, // D80/A14 + PC_3_C // D81/A15 +}; + +// Analog (Ax) pin number array +const uint32_t analogInputPin[] = { + 0, // A0, PA0 + 1, // A1, PA1 + 2, // A2, PA2 + 3, // A3, PA3 + 4, // A4, PA4 + 5, // A5, PA5 + 6, // A6, PA6 + 7, // A7, PA7 + 16, // A8, PB0 + 17, // A9, PB1 + 32, // A10, PC0 + 33, // A11, PC1 + 34, // A12, PC4 + 35, // A13, PC5 + 80, // A14, PC2_C + 81 // A15, PC3_C +}; + +/* + * @brief System Clock Configuration + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {}; + + /** Supply configuration update enable + */ + HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY); + /** Configure the main internal regulator output voltage + */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE0); + + while(!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {} + /** Initializes the RCC Oscillators according to the specified parameters + * in the RCC_OscInitTypeDef structure. + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_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 = 5; // 25Mhz / 5 = 5Mhz + RCC_OscInitStruct.PLL.PLLN = 192; // 25Mhz / 5 * 192 = 960Mhz + RCC_OscInitStruct.PLL.PLLP = 2; // 960Mhz / 2 = 480Mhz + RCC_OscInitStruct.PLL.PLLQ = 20; // 960Mhz / 20 = 48Mhz for USB + RCC_OscInitStruct.PLL.PLLR = 20; // unused + RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2; + RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE; + RCC_OscInitStruct.PLL.PLLFRACN = 0; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { + Error_Handler(); + } + /** Initializes the CPU, AHB and APB buses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2 + |RCC_CLOCKTYPE_D3PCLK1|RCC_CLOCKTYPE_D1PCLK1; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2; + RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2; + RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK) + { + Error_Handler(); + } + + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB | RCC_PERIPHCLK_QSPI + | RCC_PERIPHCLK_SDMMC | RCC_PERIPHCLK_ADC + | RCC_PERIPHCLK_LPUART1 | RCC_PERIPHCLK_USART16 + | RCC_PERIPHCLK_USART234578 | RCC_PERIPHCLK_I2C123 + | RCC_PERIPHCLK_I2C4 | RCC_PERIPHCLK_SPI123 + | RCC_PERIPHCLK_SPI45 | RCC_PERIPHCLK_SPI6; + + /* PLL1 qclk used for USB 48 Mhz */ + /* PLL1 qclk also used for FMC, QUADSPI, SDMMC, RNG, SAI */ + /* PLL2 pclk is needed for adc max 80 Mhz (p,q,r same) */ + /* PLL2 pclk also used for LP timers 2,3,4,5, SPI 1,2,3 */ + /* PLL2 qclk is needed for uart, can, spi4,5,6 80 Mhz */ + /* PLL3 r clk is needed for i2c 80 Mhz (p,q,r same) */ + PeriphClkInitStruct.PLL2.PLL2M = 15; // M DIV 15 vco 25 / 15 ~ 1.667 Mhz + PeriphClkInitStruct.PLL2.PLL2N = 96; // N MUL 96 + PeriphClkInitStruct.PLL2.PLL2P = 2; // P div 2 + PeriphClkInitStruct.PLL2.PLL2Q = 2; // Q div 2 + PeriphClkInitStruct.PLL2.PLL2R = 2; // R div 2 + // RCC_PLL1VCIRANGE_0 Clock range frequency between 1 and 2 MHz + PeriphClkInitStruct.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; + PeriphClkInitStruct.PLL2.PLL2VCOSEL = RCC_PLL2VCOMEDIUM; + PeriphClkInitStruct.PLL2.PLL2FRACN = 0; + PeriphClkInitStruct.PLL3.PLL3M = 15; // M DIV 15 vco 25 / 15 ~ 1.667 Mhz + PeriphClkInitStruct.PLL3.PLL3N = 96; // N MUL 96 + PeriphClkInitStruct.PLL3.PLL3P = 2; // P div 2 + PeriphClkInitStruct.PLL3.PLL3Q = 2; // Q div 2 + PeriphClkInitStruct.PLL3.PLL3R = 2; // R div 2 + // RCC_PLL1VCIRANGE_0 Clock range frequency between 1 and 2 MHz + PeriphClkInitStruct.PLL3.PLL3RGE = RCC_PLL3VCIRANGE_0; + PeriphClkInitStruct.PLL3.PLL3VCOSEL = RCC_PLL3VCOMEDIUM; + PeriphClkInitStruct.PLL3.PLL3FRACN = 0; + // ADC from PLL2 pclk + PeriphClkInitStruct.AdcClockSelection = RCC_ADCCLKSOURCE_PLL2; + // USB from PLL1 qclk + PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_PLL; + // QSPI from PLL1 qclk + PeriphClkInitStruct.QspiClockSelection = RCC_QSPICLKSOURCE_PLL; + // SDMMC from PLL1 qclk + PeriphClkInitStruct.SdmmcClockSelection = 0; + //PeriphClkInitStruct.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL; + // LPUART from PLL2 qclk + PeriphClkInitStruct.Lpuart1ClockSelection = 0; + //PeriphClkInitStruct.Lpuart1ClockSelection = RCC_LPUART1CLKSOURCE_PLL2; + // USART from PLL2 qclk + PeriphClkInitStruct.Usart16ClockSelection = RCC_USART16CLKSOURCE_PLL2; + // USART from PLL2 qclk + PeriphClkInitStruct.Usart234578ClockSelection = 0; + //PeriphClkInitStruct.Usart234578ClockSelection = RCC_USART234578CLKSOURCE_PLL2; + // I2C123 from PLL3 rclk + PeriphClkInitStruct.I2c123ClockSelection = RCC_I2C123CLKSOURCE_PLL3; + // I2C4 from PLL3 rclk + PeriphClkInitStruct.I2c4ClockSelection = 0; + //PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_PLL3; + // SPI123 from PLL2 pclk + PeriphClkInitStruct.Spi123ClockSelection = RCC_SPI123CLKSOURCE_PLL2; + // SPI45 from PLL2 qclk + PeriphClkInitStruct.Spi45ClockSelection = 0; + //PeriphClkInitStruct.Spi45ClockSelection = RCC_SPI45CLKSOURCE_PLL2; + // SPI6 from PLL2 qclk + PeriphClkInitStruct.Spi6ClockSelection = 0; + //PeriphClkInitStruct.Spi6ClockSelection = RCC_SPI6CLKSOURCE_PLL2; + + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { + Error_Handler(); + } +} + +#endif /* ARDUINO_GENERIC_* */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.h b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.h new file mode 100644 index 000000000000..35cf65dee9b9 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.h @@ -0,0 +1,268 @@ +/* + ******************************************************************************* + * Copyright (c) 2020-2021, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + */ +#pragma once + +/*---------------------------------------------------------------------------- + * STM32 pins number + *----------------------------------------------------------------------------*/ +#define PA0 PIN_A0 +#define PA1 PIN_A1 +#define PA2 PIN_A2 +#define PA3 PIN_A3 +#define PA4 PIN_A4 +#define PA5 PIN_A5 +#define PA6 PIN_A6 +#define PA7 PIN_A7 +#define PA8 8 +#define PA9 9 +#define PA10 10 +#define PA11 11 +#define PA12 12 +#define PA13 13 +#define PA14 14 +#define PA15 15 +#define PB0 PIN_A8 +#define PB1 PIN_A9 +#define PB2 18 +#define PB3 19 +#define PB4 20 +#define PB5 21 +#define PB6 22 +#define PB7 23 +#define PB8 24 +#define PB9 25 +#define PB10 26 +#define PB11 27 +#define PB12 28 +#define PB13 29 +#define PB14 30 +#define PB15 31 +#define PC0 PIN_A10 +#define PC1 PIN_A11 +#define PC4 PIN_A12 +#define PC5 PIN_A13 +#define PC6 36 +#define PC7 37 +#define PC8 38 +#define PC9 39 +#define PC10 40 +#define PC11 41 +#define PC12 42 +#define PC13 43 +#define PC14 44 +#define PC15 45 +#define PD0 46 +#define PD1 47 +#define PD2 48 +#define PD3 49 +#define PD4 50 +#define PD5 51 +#define PD6 52 +#define PD7 53 +#define PD8 54 +#define PD9 55 +#define PD10 56 +#define PD11 57 +#define PD12 58 +#define PD13 59 +#define PD14 60 +#define PD15 61 +#define PE0 62 +#define PE1 63 +#define PE2 64 +#define PE3 65 +#define PE4 66 +#define PE5 67 +#define PE6 68 +#define PE7 69 +#define PE8 70 +#define PE9 71 +#define PE10 72 +#define PE11 73 +#define PE12 74 +#define PE13 75 +#define PE14 76 +#define PE15 77 +#define PH0 78 +#define PH1 79 +#define PC2_C PIN_A14 +#define PC3_C PIN_A15 +#define PC2 PC2_C +#define PC3 PC3_C + +// Alternate pins number +#define PA0_ALT1 (PA0 | ALT1) +#define PA1_ALT1 (PA1 | ALT1) +#define PA1_ALT2 (PA1 | ALT2) +#define PA2_ALT1 (PA2 | ALT1) +#define PA2_ALT2 (PA2 | ALT2) +#define PA3_ALT1 (PA3 | ALT1) +#define PA3_ALT2 (PA3 | ALT2) +#define PA4_ALT1 (PA4 | ALT1) +#define PA4_ALT2 (PA4 | ALT2) +#define PA5_ALT1 (PA5 | ALT1) +#define PA6_ALT1 (PA6 | ALT1) +#define PA7_ALT1 (PA7 | ALT1) +#define PA7_ALT2 (PA7 | ALT2) +#define PA7_ALT3 (PA7 | ALT3) +#define PA9_ALT1 (PA9 | ALT1) +#define PA10_ALT1 (PA10 | ALT1) +#define PA11_ALT1 (PA11 | ALT1) +#define PA12_ALT1 (PA12 | ALT1) +#define PA15_ALT1 (PA15 | ALT1) +#define PA15_ALT2 (PA15 | ALT2) +#define PB0_ALT1 (PB0 | ALT1) +#define PB0_ALT2 (PB0 | ALT2) +#define PB1_ALT1 (PB1 | ALT1) +#define PB1_ALT2 (PB1 | ALT2) +#define PB3_ALT1 (PB3 | ALT1) +#define PB3_ALT2 (PB3 | ALT2) +#define PB4_ALT1 (PB4 | ALT1) +#define PB4_ALT2 (PB4 | ALT2) +#define PB5_ALT1 (PB5 | ALT1) +#define PB5_ALT2 (PB5 | ALT2) +#define PB6_ALT1 (PB6 | ALT1) +#define PB6_ALT2 (PB6 | ALT2) +#define PB7_ALT1 (PB7 | ALT1) +#define PB8_ALT1 (PB8 | ALT1) +#define PB8_ALT2 (PB8 | ALT2) +#define PB9_ALT1 (PB9 | ALT1) +#define PB9_ALT2 (PB9 | ALT2) +#define PB14_ALT1 (PB14 | ALT1) +#define PB14_ALT2 (PB14 | ALT2) +#define PB15_ALT1 (PB15 | ALT1) +#define PB15_ALT2 (PB15 | ALT2) +#define PC0_ALT1 (PC0 | ALT1) +#define PC0_ALT2 (PC0 | ALT2) +#define PC1_ALT1 (PC1 | ALT1) +#define PC1_ALT2 (PC1 | ALT2) +#define PC4_ALT1 (PC4 | ALT1) +#define PC5_ALT1 (PC5 | ALT1) +#define PC6_ALT1 (PC6 | ALT1) +#define PC6_ALT2 (PC6 | ALT2) +#define PC7_ALT1 (PC7 | ALT1) +#define PC7_ALT2 (PC7 | ALT2) +#define PC8_ALT1 (PC8 | ALT1) +#define PC9_ALT1 (PC9 | ALT1) +#define PC10_ALT1 (PC10 | ALT1) +#define PC11_ALT1 (PC11 | ALT1) + +#define NUM_DIGITAL_PINS 82 +#define NUM_DUALPAD_PINS 2 +#define NUM_ANALOG_INPUTS 16 + +// On-board LED pin number +#ifndef LED_BUILTIN + #define LED_BUILTIN PNUM_NOT_DEFINED +#endif + +// On-board user button +#ifndef USER_BTN + #define USER_BTN PNUM_NOT_DEFINED +#endif + +// SPI definitions +#ifndef PIN_SPI_SS + #define PIN_SPI_SS PA4 +#endif +#ifndef PIN_SPI_SS1 + #define PIN_SPI_SS1 PA15 +#endif +#ifndef PIN_SPI_SS2 + #define PIN_SPI_SS2 PNUM_NOT_DEFINED +#endif +#ifndef PIN_SPI_SS3 + #define PIN_SPI_SS3 PNUM_NOT_DEFINED +#endif +#ifndef PIN_SPI_MOSI + #define PIN_SPI_MOSI PA7 +#endif +#ifndef PIN_SPI_MISO + #define PIN_SPI_MISO PA6 +#endif +#ifndef PIN_SPI_SCK + #define PIN_SPI_SCK PA5 +#endif + +// I2C definitions +#ifndef PIN_WIRE_SDA + #define PIN_WIRE_SDA PB7 +#endif +#ifndef PIN_WIRE_SCL + #define PIN_WIRE_SCL PB6 +#endif + +// Timer Definitions +// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin +#ifndef TIMER_TONE + #define TIMER_TONE TIM6 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM7 +#endif + +// UART Definitions +#ifndef SERIAL_UART_INSTANCE + #define SERIAL_UART_INSTANCE 4 +#endif + +// Default pin used for generic 'Serial' instance +// Mandatory for Firmata +#ifndef PIN_SERIAL_RX + #define PIN_SERIAL_RX PA1 +#endif +#ifndef PIN_SERIAL_TX + #define PIN_SERIAL_TX PA0 +#endif + +// Extra HAL modules +#if !defined(HAL_DAC_MODULE_DISABLED) + #define HAL_DAC_MODULE_ENABLED +#endif +#if !defined(HAL_ETH_MODULE_DISABLED) + #define HAL_ETH_MODULE_ENABLED +#endif +#if !defined(HAL_QSPI_MODULE_DISABLED) + #define HAL_QSPI_MODULE_ENABLED +#endif +#if !defined(HAL_SD_MODULE_DISABLED) + #define HAL_SD_MODULE_ENABLED +#endif + +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus + // These serial port names are intended to allow libraries and architecture-neutral + // sketches to automatically default to the correct port name for a particular type + // of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, + // the first hardware serial port whose RX/TX pins are not dedicated to another use. + // + // SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor + // + // SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial + // + // SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library + // + // SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. + // + // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX + // pins are NOT connected to anything by default. + #ifndef SERIAL_PORT_MONITOR + #define SERIAL_PORT_MONITOR Serial + #endif + #ifndef SERIAL_PORT_HARDWARE + #define SERIAL_PORT_HARDWARE Serial + #endif +#endif diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board.cpp b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board.cpp rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board.cpp diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board/board.h b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/board/board.h rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/common.inc b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/common.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/common.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/common.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/extra_libs.inc b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/extra_libs.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/extra_libs.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/extra_libs.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/flash.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/flash.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/flash.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/flash.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103z_dfu.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103z_dfu.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103z_dfu.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103z_dfu.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103zc.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103zc.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103zc.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103zc.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103zd.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103zd.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103zd.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103zd.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103ze.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103ze.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/stm32f103ze.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103ze.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/vector_symbols.inc b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/vector_symbols.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/ld/vector_symbols.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/vector_symbols.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/pins_arduino.h b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/pins_arduino.h similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/pins_arduino.h rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/pins_arduino.h diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/variant.h b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/variant.h similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/variant.h rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/variant.h diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/boards.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/boards.cpp diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards_setup.cpp b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/boards_setup.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards_setup.cpp rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/boards_setup.cpp diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/start.S b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/start.S similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/start.S rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/start.S diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/start_c.c b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/start_c.c similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/start_c.c rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/start_c.c diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/syscalls.c b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/syscalls.c similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/syscalls.c rename to buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/syscalls.c diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/board.cpp b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/board.cpp rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board.cpp diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/board/board.h b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/board/board.h rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/bootloader.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/bootloader.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/bootloader.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/bootloader.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/common.inc b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/common.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/common.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/common.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/extra_libs.inc b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/extra_libs.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/extra_libs.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/extra_libs.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/flash.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/flash.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/flash.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/flash.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/jtag.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/jtag.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/jtag.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/jtag.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-flash.inc b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/mem-flash.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-flash.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/mem-flash.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-jtag.inc b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/mem-jtag.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-jtag.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/mem-jtag.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-ram.inc b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/mem-ram.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/mem-ram.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/mem-ram.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/ram.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/ram.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/ram.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/ram.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rb.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103rb.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rb.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103rb.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rb_bootloader.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103rb_bootloader.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rb_bootloader.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103rb_bootloader.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rc.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103rc.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rc.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103rc.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rc_bootloader.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103rc_bootloader.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103rc_bootloader.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103rc_bootloader.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103re.ld b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103re.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/stm32f103re.ld rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/stm32f103re.ld diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/vector_symbols.inc b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/vector_symbols.inc similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/ld/vector_symbols.inc rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/ld/vector_symbols.inc diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/pins_arduino.h b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/pins_arduino.h similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/pins_arduino.h rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/pins_arduino.h diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/variant.h b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/variant.h similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/variant.h rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/variant.h diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/boards.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/boards.cpp diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards_setup.cpp b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/boards_setup.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards_setup.cpp rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/boards_setup.cpp diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/start.S b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/start.S similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/start.S rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/start.S diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/start_c.c b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/start_c.c similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/start_c.c rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/start_c.c diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/syscalls.c b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/syscalls.c similarity index 100% rename from buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/syscalls.c rename to buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/wirish/syscalls.c diff --git a/buildroot/share/fonts/genpages.c b/buildroot/share/fonts/genpages.c index dea5b05c5c80..8009e553fa68 100644 --- a/buildroot/share/fonts/genpages.c +++ b/buildroot/share/fonts/genpages.c @@ -66,7 +66,7 @@ wchar_t get_val_utf82uni(uint8_t *pstart) { */ uint8_t* get_utf8_value(uint8_t *pstart, wchar_t *pval) { uint32_t val = 0; - uint8_t *p = pstart; + const uint8_t *p = pstart; /*size_t maxlen = strlen(pstart);*/ assert(NULL != pstart); diff --git a/buildroot/share/git/mfconfig b/buildroot/share/git/mfconfig index d3e0b67b3e40..b379317d9866 100755 --- a/buildroot/share/git/mfconfig +++ b/buildroot/share/git/mfconfig @@ -34,8 +34,8 @@ 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"} +IMPORT=${2:-"import-2.1.x"} +EXPORT=${3:-"bugfix-2.1.x"} echo -n "Doing grhh ... " ; grhh ; echo @@ -52,7 +52,7 @@ if [[ $ACTION == "manual" ]]; then git checkout $IMPORT || exit # Reset from the latest complete state - #git reset --hard bugfix-2.0.x + #git reset --hard bugfix-2.1.x cp "$MARLINREPO/Marlin/"Configuration*.h "$CDEF/" #git add . && git commit -m "Changes from Marlin ($(date '+%Y-%m-%d %H:%M'))." @@ -110,53 +110,15 @@ if [[ $ACTION == "init" ]]; then ((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..." + echo "- Initializing configs to default state..." - find "$CEXA" -name $BC ! -path */delta/* -print0 \ + find "$CEXA" -name $BC -print0 \ | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done - find "$CEXA" -name $AC ! -path */delta/* -print0 \ + find "$CEXA" -name $AC -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 + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset configs..." >/dev/null # Update the %VERSION% in the README.md file VERS=$( echo $EXPORT | $SED 's/release-//' ) diff --git a/buildroot/share/git/mffp b/buildroot/share/git/mffp index ab4dd4c0b771..6fe52d47e5a3 100755 --- a/buildroot/share/git/mffp +++ b/buildroot/share/git/mffp @@ -3,7 +3,7 @@ # mffp [1|2] [ref] # # Push the given commit (or HEAD) upstream immediately. -# By default: `git push upstream HEAD:bugfix-2.0.x` +# By default: `git push upstream HEAD:bugfix-2.1.x` # usage() { echo "usage: `basename $0` [1|2] [ref]" 1>&2 ; } diff --git a/buildroot/share/git/mfinfo b/buildroot/share/git/mfinfo index 0c2113d92293..3f183b8fd8f0 100755 --- a/buildroot/share/git/mfinfo +++ b/buildroot/share/git/mfinfo @@ -7,13 +7,13 @@ # - Remote (upstream) Org name (MarlinFirmware) # - Remote (origin) Org name (your Github username) # - Repo Name (Marlin, MarlinDocumentation) -# - PR Target branch (e.g., bugfix-2.0.x) +# - PR Target branch (e.g., bugfix-2.1.x) # - Branch Arg (the branch argument or current branch) # - Current Branch # # Example output # > mfinfo -q ongoing -# MarlinFirmware john.doe Marlin bugfix-2.0.x ongoing bugfix-2.0.x -q +# MarlinFirmware john.doe Marlin bugfix-2.1.x ongoing bugfix-2.1.x -q # CURR=$(git branch 2>/dev/null | grep ^* | sed 's/\* //g') @@ -55,7 +55,7 @@ while [[ $# -gt 0 ]]; do done case "$REPO" in - Marlin ) TARG=bugfix-2.0.x ; ((INDEX == 1)) && TARG=bugfix-1.1.x ; [[ $BRANCH =~ ^[12]$ ]] && USAGE=1 ;; + Marlin ) TARG=bugfix-2.1.x ; ((INDEX == 1)) && TARG=bugfix-1.1.x ; [[ $BRANCH =~ ^[12]$ ]] && USAGE=1 ;; Configurations ) TARG=import-2.0.x ;; MarlinDocumentation ) TARG=master ;; AutoBuildMarlin ) TARG=master ;; diff --git a/buildroot/share/git/mfprep b/buildroot/share/git/mfprep index b329d7d8c5d9..0c9e54fe8de4 100755 --- a/buildroot/share/git/mfprep +++ b/buildroot/share/git/mfprep @@ -2,54 +2,69 @@ # # mfprep tag1 [tag2] # -# Find commits in bugfix-2.0.x not yet in 2.0.x +# Find commits in bugfix-2.1.x that are not yet in 2.0.x. +# +# Specify a version tag to start from, and optional version tag to end at. +# For bugfix-2.1.x the tag will be prefixed by dev- to distinguish it from the version tag, +# so at every release be sure to create a dev- tag and publish it to origin. # SED=$(which gsed sed | head -n1) SELF=`basename "$0"` +DRYRUN=0 [[ $# < 1 || $# > 2 ]] && { echo "Usage $SELF tag1 [tag2]" ; exit 1 ; } TAG1=$1 TAG2=${2:-"HEAD"} +DEST=2.1.x + # Validate that the required tags exist -MTAG=`git tag | grep -e "^bf-$TAG1\$"` -[[ -n $MTAG ]] || { echo "Can't find tag bf-$TAG1" ; exit 1 ; } +MTAG=`git tag | grep -e "^dev-$TAG1\$"` +[[ -n "$MTAG" ]] || { echo "Can't find tag dev-$TAG1" ; exit 1 ; } MTAG=`git tag | grep -e "^$TAG1\$"` -[[ -n $MTAG ]] || { echo "Can't find tag $TAG1" ; exit 1 ; } +[[ -n "$MTAG" ]] || { echo "Can't find tag $TAG1" ; exit 1 ; } -# Generate log of recent commits for bugfix-2.0.x and 2.0.x +# Generate log of recent commits for bugfix-2.1.x and DEST TMPDIR=`mktemp -d` LOGB="$TMPDIR/log-bf.txt" -LOG2="$TMPDIR/log-20x.txt" +LOG2="$TMPDIR/log-2x.txt" TMPF="$TMPDIR/tmp.txt" -SCRF="$TMPDIR/update-20x.sh" +SCRF="$TMPDIR/update-$DEST.sh" -git checkout bugfix-2.0.x -git log --pretty="[%h] %s" bf-$TAG1..$TAG2 | grep -v '\[cron\]' | $SED '1!G;h;$!d' >"$LOGB" +git checkout bugfix-2.1.x +git log --pretty="[%h] %s" dev-$TAG1..$TAG2 | grep -v '\[cron\]' | $SED '1!G;h;$!d' >"$LOGB" -git checkout 2.0.x -git log --pretty="[%h] %s" $TAG1..$TAG2 | $SED '1!G;h;$!d' >"$LOG2" || { echo "Can't find tag bf-$TAG1" ; exit 1 ; } +git checkout $DEST +git log --pretty="[%h] %s" $TAG1..$TAG2 | $SED '1!G;h;$!d' >"$LOG2" || { echo "Can't find tag dev-$TAG1" ; exit 1 ; } -# Go through commit text from 2.0.x removing all matches from the bugfix log +# Go through commit text from DEST removing all matches from the bugfix log cat "$LOG2" | while read line; do - #echo "... $line" - if [[ $line =~ (\(#[0-9]{5}\))$ ]]; then - PATT=${BASH_REMATCH[1]} + if [[ $line =~ \(((#[0-9]{5}),* *)((#[0-9]{5}),* *)?((#[0-9]{5}),* *)?((#[0-9]{5}),* *)?((#[0-9]{5}),* *)?((#[0-9]{5}),* *)?\)$ ]]; then + PATT="" + for i in ${!BASH_REMATCH[@]}; do + if ((i > 0 && (i % 2 == 0))); then + if [[ -n "${BASH_REMATCH[i]}" ]]; then + [[ -n "$PATT" ]] && PATT="$PATT|" + PATT="$PATT${BASH_REMATCH[i]}" + fi + fi + done #echo "... $PATT" + [[ -n "$PATT" ]] && { grep -vE "$PATT" "$LOGB" >"$TMPF" ; cp "$TMPF" "$LOGB" ; } else PATT=$( $SED -E 's/^\[[0-9a-f]{10}\]( . )?(.+)$/\2/' <<<"$line" ) + [[ -n "$PATT" ]] && { grep -v "$PATT" "$LOGB" >"$TMPF" ; cp "$TMPF" "$LOGB" ; } fi - [[ -n $PATT ]] && { grep -v "$PATT" "$LOGB" >"$TMPF" ; cp "$TMPF" "$LOGB" ; } done # Convert remaining commits into git commands -echo -e "#!/usr/bin/env bash\nset -e\ngit checkout 2.0.x\n" >"$TMPF" +echo -e "#!/usr/bin/env bash\nset -e\ngit checkout ${DEST}\n" >"$TMPF" cat "$LOGB" | while read line; do if [[ $line =~ ^\[([0-9a-f]{10})\]\ *(.*)$ ]]; then CID=${BASH_REMATCH[1]} @@ -60,6 +75,6 @@ cat "$LOGB" | while read line; do fi done mv "$TMPF" "$SCRF" -chmod ug+x "$SCRF" +chmod +x "$SCRF" -open "$TMPDIR" +((DRYRUN)) && rm -r "$TMPDIR" || open "$TMPDIR" diff --git a/buildroot/share/pixmaps/logo/marlin-outrun-nf-500.png b/buildroot/share/pixmaps/logo/marlin-outrun-nf-500.png new file mode 100644 index 000000000000..e36a3eb5c216 Binary files /dev/null and b/buildroot/share/pixmaps/logo/marlin-outrun-nf-500.png differ diff --git a/buildroot/share/scripts/g29_auto.py b/buildroot/share/scripts/g29_auto.py index ca36346dd9dd..5cf27b996865 100755 --- a/buildroot/share/scripts/g29_auto.py +++ b/buildroot/share/scripts/g29_auto.py @@ -1,13 +1,13 @@ #!/usr/bin/env python -# This file is for preprocessing gcode and the new G29 Autobedleveling from Marlin -# It will analyse the first 2 Layer and return the maximum size for this part -# After this it will replace with g29_keyword = ';MarlinG29Script' with the new G29 LRFB -# the new file will be created in the same folder. +# This file is for preprocessing G-code and the new G29 Auto bed leveling from Marlin +# It will analyze the first 2 layers and return the maximum size for this part +# Then it will be replaced with g29_keyword = ';MarlinG29Script' with the new G29 LRFB. +# The new file will be created in the same folder. from __future__ import print_function -# your gcode-file/folder +# Your G-code file/folder folder = './' my_file = 'test.gcode' diff --git a/buildroot/tests/BIGTREE_GTR_V1_0 b/buildroot/tests/BIGTREE_GTR_V1_0 index 93342ed4a472..d6eccaff07dc 100755 --- a/buildroot/tests/BIGTREE_GTR_V1_0 +++ b/buildroot/tests/BIGTREE_GTR_V1_0 @@ -22,7 +22,7 @@ exec_test $1 $2 "BigTreeTech GTR | 8 Extruders | Auto-Fan | Mixed TMC Drivers | 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 \ + Z_DRIVER_TYPE A4988 Z2_DRIVER_TYPE A4988 Z3_DRIVER_TYPE A4988 Z4_DRIVER_TYPE A4988 \ DEFAULT_Kp_LIST '{ 22.2, 20.0, 21.0, 19.0, 18.0 }' DEFAULT_Ki_LIST '{ 1.08 }' DEFAULT_Kd_LIST '{ 114.0, 112.0, 110.0, 108.0 }' opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_SLOW_FIRST_PRIME TOOLCHANGE_FS_PRIME_FIRST_USED \ PID_PARAMS_PER_HOTEND Z_MULTI_ENDSTOPS @@ -37,7 +37,8 @@ opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ MPC_BLOCK_HEAT_CAPACITY '{ 16.7f, 16.7f, 16.7f }' \ MPC_SENSOR_RESPONSIVENESS '{ 0.22f, 0.22f, 0.22f }' \ MPC_AMBIENT_XFER_COEFF '{ 0.068f, 0.068f, 0.068f }' \ - MPC_AMBIENT_XFER_COEFF_FAN255 '{ 0.097f, 0.097f, 0.097f }' + MPC_AMBIENT_XFER_COEFF_FAN255 '{ 0.097f, 0.097f, 0.097f }' \ + FILAMENT_HEAT_CAPACITY_PERMM '{ 5.6e-3f, 3.6e-3f, 5.6e-3f }' opt_enable SWITCHING_TOOLHEAD TOOL_SENSOR MPCTEMP MPC_EDIT_MENU MPC_AUTOTUNE_MENU opt_disable PIDTEMP exec_test $1 $2 "BigTreeTech GTR | MPC | Switching Toolhead | Tool Sensors" "$3" diff --git a/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive b/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive index 34bf77be27a4..78aec1329558 100755 --- a/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive +++ b/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive @@ -10,7 +10,7 @@ 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 LEVEL_BED_CORNERS LEVEL_CORNERS_USE_PROBE \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER BLTOUCH LCD_BED_TRAMMING BED_TRAMMING_USE_PROBE \ NEOPIXEL_LED Z_SAFE_HOMING FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE # Not necessary to enable auto-fan for all extruders to hit problematic code paths opt_set E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 NEOPIXEL_PIN PF13 \ diff --git a/buildroot/tests/BIGTREE_SKR_PRO b/buildroot/tests/BIGTREE_SKR_PRO index 2503b28544ad..2f1075c7ef22 100755 --- a/buildroot/tests/BIGTREE_SKR_PRO +++ b/buildroot/tests/BIGTREE_SKR_PRO @@ -26,7 +26,7 @@ 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 +opt_enable LASER_FEATURE LASER_SAFETY_TIMEOUT_MS REPRAP_DISCOUNT_SMART_CONTROLLER exec_test $1 $2 "BigTreeTech SKR Pro | Laser (Percent) | Cooling | LCD" "$3" # clean up diff --git a/buildroot/tests/BTT_SKR_SE_BX b/buildroot/tests/BTT_SKR_SE_BX index b5d6f6de8398..199cff14b9b0 100755 --- a/buildroot/tests/BTT_SKR_SE_BX +++ b/buildroot/tests/BTT_SKR_SE_BX @@ -9,10 +9,8 @@ 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" +use_example_configs BIQU/BX +exec_test $1 $2 "BIQU/BX" "$3" # clean up restore_configs diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index 9b968cbd8d4d..a2f3fda7a7ac 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -35,7 +35,7 @@ exec_test $1 $2 "RAMPS4DUE_EFB with ABL (Bilinear), ExtUI, S-Curve, many options # RADDS with BLTouch, ABL(B), 3 x Z auto-align # restore_configs -opt_set MOTHERBOARD BOARD_RADDS NUM_Z_STEPPER_DRIVERS 3 +opt_set MOTHERBOARD BOARD_RADDS Z_DRIVER_TYPE A4988 Z2_DRIVER_TYPE A4988 Z3_DRIVER_TYPE A4988 opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \ Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_STEPPER_XY Z_SAFE_HOMING pins_set ramps/RAMPS X_MAX_PIN -1 diff --git a/buildroot/tests/FYSETC_F6 b/buildroot/tests/FYSETC_F6 index 9306686af5ce..17f8eb42b1e2 100755 --- a/buildroot/tests/FYSETC_F6 +++ b/buildroot/tests/FYSETC_F6 @@ -10,7 +10,7 @@ set -e # Build with the default configurations # restore_configs -opt_set MOTHERBOARD BOARD_FYSETC_F6_13 +opt_set MOTHERBOARD BOARD_FYSETC_F6_13 LCD_SERIAL_PORT 1 opt_enable DGUS_LCD_UI_FYSETC exec_test $1 $2 "FYSETC F6 1.3 with DGUS" "$3" diff --git a/buildroot/tests/Index_Mobo_Rev03 b/buildroot/tests/Index_Mobo_Rev03 deleted file mode 100755 index 501386489df0..000000000000 --- a/buildroot/tests/Index_Mobo_Rev03 +++ /dev/null @@ -1,13 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for Index_Mobo_Rev03 -# - -# exit on first failure -set -e - -use_example_configs Index/REV_03 -exec_test $1 $2 "Index REV03 Pick and Place" "$3" - -# cleanup -restore_configs diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index 34ae40d18a96..9fb7479d9921 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -15,7 +15,7 @@ set -e 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 + NEOPIXEL_TYPE NEO_RGB 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" diff --git a/buildroot/tests/LPC1769 b/buildroot/tests/LPC1769 index 3fe99734ca6b..086dffffc92c 100755 --- a/buildroot/tests/LPC1769 +++ b/buildroot/tests/LPC1769 @@ -21,7 +21,7 @@ opt_set MOTHERBOARD BOARD_SMOOTHIEBOARD \ opt_enable TFTGLCD_PANEL_SPI SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ MAX31865_SENSOR_OHMS_0 MAX31865_CALIBRATION_OHMS_0 \ FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR G29_RETRY_AND_RECOVER Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ - BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET LEVEL_CORNERS_USE_PROBE LEVEL_CORNERS_VERIFY_RAISED \ + BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BED_TRAMMING_USE_PROBE BED_TRAMMING_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 diff --git a/buildroot/tests/Opulo_Lumen_REV3 b/buildroot/tests/Opulo_Lumen_REV3 new file mode 100755 index 000000000000..ddd8e1f3c9aa --- /dev/null +++ b/buildroot/tests/Opulo_Lumen_REV3 @@ -0,0 +1,13 @@ +#!/usr/bin/env bash +# +# Build tests for Opulo_Lumen_REV3 +# + +# exit on first failure +set -e + +use_example_configs Opulo/Lumen_REV3 +exec_test $1 $2 "Opulo Lumen REV3 Pick-and-Place" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/SAMD51_grandcentral_m4 b/buildroot/tests/SAMD51_grandcentral_m4 index 92a62c9d37a4..e6e27d8cb8c9 100755 --- a/buildroot/tests/SAMD51_grandcentral_m4 +++ b/buildroot/tests/SAMD51_grandcentral_m4 @@ -16,7 +16,6 @@ opt_set MOTHERBOARD BOARD_AGCM4_RAMPS_144 SERIAL_PORT -1 \ 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 \ diff --git a/buildroot/tests/STM32F103RC_meeb b/buildroot/tests/STM32F103RC_meeb_maple similarity index 100% rename from buildroot/tests/STM32F103RC_meeb rename to buildroot/tests/STM32F103RC_meeb_maple diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index 6440c5679224..bf1634544937 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -13,20 +13,14 @@ use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING BLTOUCH AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING exec_test $1 $2 "Ender 3 v2 with CrealityUI" "$3" -use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" -opt_disable DWIN_CREALITY_LCD -opt_enable BLTOUCH AUTO_BED_LEVELING_UBL Z_SAFE_HOMING INDIVIDUAL_AXIS_HOMING_SUBMENU LCD_SET_PROGRESS_MANUALLY STATUS_MESSAGE_SCROLLING BAUD_RATE_GCODE \ - DWIN_LCD_PROUI SOUND_MENU_ITEM PRINTCOUNTER -exec_test $1 $2 "Ender 3 v2 with ProUI" "$3" - -use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" -opt_disable DWIN_CREALITY_LCD -opt_enable DWIN_CREALITY_LCD_JYERSUI AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY -exec_test $1 $2 "Ender 3 v2 with JyersUI" "$3" - -use_example_configs "Creality/Ender-3 V2/CrealityV422/MarlinUI" -opt_add SDCARD_EEPROM_EMULATION AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING -exec_test $1 $2 "Ender 3 v2 with MarlinUI" "$3" +use_example_configs "Creality/Ender-3 S1/STM32F1" +opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CONFIGURATION_EMBEDDING CANCEL_OBJECTS FWRETRACT +opt_enable DWIN_LCD_PROUI INDIVIDUAL_AXIS_HOMING_SUBMENU LCD_SET_PROGRESS_MANUALLY STATUS_MESSAGE_SCROLLING \ + SOUND_MENU_ITEM PRINTCOUNTER NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_SENSOR \ + BLTOUCH Z_SAFE_HOMING AUTO_BED_LEVELING_UBL MESH_EDIT_MENU \ + LIMITED_MAX_FR_EDITING LIMITED_MAX_ACCEL_EDITING LIMITED_JERK_EDITING BAUD_RATE_GCODE +opt_set PREHEAT_3_LABEL '"CUSTOM"' PREHEAT_3_TEMP_HOTEND 240 PREHEAT_3_TEMP_BED 60 PREHEAT_3_FAN_SPEED 128 +exec_test $1 $2 "Ender-3 S1 with ProUI" "$3" restore_configs opt_set MOTHERBOARD BOARD_CREALITY_V452 SERIAL_PORT 1 diff --git a/buildroot/tests/STM32F401RC_creality b/buildroot/tests/STM32F401RC_creality new file mode 100755 index 000000000000..380711d061c2 --- /dev/null +++ b/buildroot/tests/STM32F401RC_creality @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F401RC_creality +# + +# exit on first failure +set -e + +use_example_configs "Creality/Ender-3 V2/CrealityV422/MarlinUI" +opt_add SDCARD_EEPROM_EMULATION AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING +opt_set MOTHERBOARD BOARD_CREALITY_V24S1_301F4 +exec_test $1 $2 "Ender 3 v2 with MarlinUI" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/mega1280 b/buildroot/tests/mega1280 index a7f25953acd0..5bf37289ba61 100755 --- a/buildroot/tests/mega1280 +++ b/buildroot/tests/mega1280 @@ -39,7 +39,7 @@ exec_test $1 $2 "(No PWM)" "$3" restore_configs opt_set MOTHERBOARD BOARD_ZRIB_V52 \ LCD_LANGUAGE pt REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 \ - EXTRUDERS 2 TEMP_SENSOR_1 1 + EXTRUDERS 2 TEMP_SENSOR_1 1 X2_DRIVER_TYPE A4988 opt_enable USE_XMAX_PLUG DUAL_X_CARRIAGE REPRAPWORLD_KEYPAD exec_test $1 $2 "ZRIB_V52 | DUAL_X_CARRIAGE" "$3" diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 3677abf60ef0..969b3b14ccbc 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -12,6 +12,14 @@ set -e #restore_configs #exec_test $1 $2 "Default Configuration" "$3" +# +# Build with no source filers +# +restore_configs +ci_src_filter -n +exec_test $1 $2 "Default Configuration | no source filtering" "$3" +ci_src_filter -y + # # Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders # @@ -179,9 +187,9 @@ opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_C 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 "MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 12864 LCD | meatpack | SERIAL_PORT_2 " "$3" +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT MEATPACK_ON_SERIAL_PORT_1 \ + LASER_FEATURE LASER_SAFETY_TIMEOUT_MS LASER_COOLANT_FLOW_METER AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN +exec_test $1 $2 "MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 12864 LCD | meatpack | Laser Safety Timeout | M3 Power Sync | Trap Power Smoothing | SERIAL_PORT_2 " "$3" # # Test Laser features with 44780 LCD @@ -193,9 +201,9 @@ opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_C 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 PRINTCOUNTER \ - LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER I2C_AMMETER -exec_test $1 $2 "MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" +opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT PRINTCOUNTER I2C_AMMETER \ + LASER_FEATURE LASER_SAFETY_TIMEOUT_MS LASER_COOLANT_FLOW_METER AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN +exec_test $1 $2 "MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Laser Safety Timeout | Flowmeter | 44780 LCD " "$3" # # Test redundant temperature sensors + MAX TC diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index e696dce96ec3..167f6d89aae2 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -24,7 +24,7 @@ opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_P 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 \ + PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 LCD_BED_TRAMMING BED_TRAMMING_INCLUDE_CENTER \ 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 \ @@ -51,12 +51,13 @@ opt_set MOTHERBOARD BOARD_RAMBO \ 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 }' + BED_TRAMMING_LEVELING_ORDER '{ LF, RF }' \ + X2_DRIVER_TYPE A4988 Y2_DRIVER_TYPE A4988 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 \ + S_CURVE_ACCELERATION X_DUAL_ENDSTOPS Y_DUAL_ENDSTOPS \ ADAPTIVE_STEP_SMOOTHING CNC_COORDINATE_SYSTEMS GCODE_MOTION_MODES \ - LEVEL_BED_CORNERS LEVEL_CENTER_TOO + LCD_BED_TRAMMING BED_TRAMMING_INCLUDE_CENTER opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS exec_test $1 $2 "Rambo CNC Configuration" "$3" diff --git a/buildroot/tests/teensy35 b/buildroot/tests/teensy35 index 09e8cee58ef3..64ce4e65505a 100755 --- a/buildroot/tests/teensy35 +++ b/buildroot/tests/teensy35 @@ -101,7 +101,7 @@ 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_set MOTHERBOARD BOARD_TEENSY35_36 Z_DRIVER_TYPE A4988 Z2_DRIVER_TYPE A4988 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" diff --git a/buildroot/tests/teensy41 b/buildroot/tests/teensy41 index 1affd7c89e12..56bd5043c736 100755 --- a/buildroot/tests/teensy41 +++ b/buildroot/tests/teensy41 @@ -105,7 +105,7 @@ 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_set MOTHERBOARD BOARD_TEENSY41 Z_DRIVER_TYPE A4988 Z2_DRIVER_TYPE A4988 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" diff --git a/buildroot/web-ui/data/www/index.html b/buildroot/web-ui/data/www/index.html index 54bcc13d7386..1a8db1cafb04 100644 --- a/buildroot/web-ui/data/www/index.html +++ b/buildroot/web-ui/data/www/index.html @@ -456,7 +456,7 @@
- +
diff --git a/config/README.md b/config/README.md index 4bd6ab851e52..b19527ccc30a 100644 --- a/config/README.md +++ b/config/README.md @@ -2,8 +2,8 @@ Marlin configurations for specific machines are now maintained in their own repository at: -## https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.0.x +## https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.1.x -Configuration files for use with the nightly `bugfix-2.0.x` branch can be downloaded from: +Configuration files for use with the nightly `bugfix-2.1.x` branch can be downloaded from: -## https://github.com/MarlinFirmware/Configurations/archive/bugfix-2.0.x.zip +## https://github.com/MarlinFirmware/Configurations/archive/bugfix-2.1.x.zip diff --git a/docker/Dockerfile b/docker/Dockerfile index 903b8b71fd32..7d32f9c63758 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -1,7 +1,7 @@ FROM python:3.9.0-buster -RUN pip install -U https://github.com/platformio/platformio-core/archive/develop.zip -RUN platformio update +RUN pip install -U platformio +RUN pio upgrade --dev # To get the test platforms RUN pip install PyYaml #ENV PATH /code/buildroot/bin/:/code/buildroot/tests/:${PATH} diff --git a/docs/Cutter.md b/docs/Cutter.md new file mode 100644 index 000000000000..c78b0551a0ac --- /dev/null +++ b/docs/Cutter.md @@ -0,0 +1,137 @@ +### Introduction + +With Marlin version 2.0.9.x or higher, Laser improvements were introduced that enhance inline functionality. Previously the inline feature option was not operational without enabling and recompiling the source. Also with inline enabled the base features are not functional. With v2.0.9.x new functionality is added which allows the standard and inline modes to be G-Code selectable and also compatible with each other. Additionally an experimental dynamic mode is also available. Spindle operational features are available with defines and recompiling. + +### Architecture + +Laser selectable feature capability is defined through 4 global mode flags within gcode ,laser/spindle, planner and stepper routines. The default mode maintains the standard laser function. G-Codes are received, processed and parsed to determine what mode to set through M3, M4 and M5 commands. When the inline mode parameter set is detected, laser power processing will be driven through the planner and stepper routines. Handling of the initial power values and settings are performed by G-Code parsing and the laser/spindle routines. + +Inline power feeds from the block->inline_power variable into the planner's laser.power when in continuous power mode. Further power adjustment will be applied if the laser power trap feature is active otherwise laser.power is used as set in the stepper for the entire block. When laser power trap is active the power levels are step incremented during acceleration and step decremented during deceleration. + +Two additional power sets are fed in the planner by features laser power sync and laser fan power sync. Both of these power sets are done with planner sync block bit flags. With laser power sync, when the bit flag is matched the global block laser.power value is updated from laser/spindle standard M3 S-Value power sets. For laser fan sync, power values are updated into the planner block->fan_speed[i] variable from fan G-Code S-Value sets. + +With dynamic inline power mode, F-Value feedrate sets are processed with cutter.calc_dynamic_power() and fed into the planner laser.power value. + +Irrespective of what laser power value source is used, the final laser output pin is always updated using the laser/spindle code. Specifically the apply_power(value) call is used to set the laser or spindle output. This call permits safe power control in the event that a sensor fault occurs. + +Note: Spindle operation is not selectable with G-Codes at this time. + +The following flow charts depict the flow control logic for spindle and laser operations in the code base. + +#### Spindle Mode Logic: + + ┌──────────┐ ┌───────────┐ ┌───────────┐ + │M3 S-Value│ │Dir !same ?│ │Stepper │ + │Spindle │ │stop & wait│ │processes │ + ┌──┤Clockwise ├──┤ & start ├──┤moves │ + ┌─────┐ │ │ │ │spindle │ │ │ + │GCode│ │ └──────────┘ └───────────┘ └───────────┘ + │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ + └─────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ + ├──┤Spindle ├──┤stop & wait├──┤processes │ + │ │Counter │ │& start │ │moves │ + │ │Clockwise │ │spindle │ │ │ + │ └──────────┘ └───────────┘ └───────────┘ + │ ┌──────────┐ ┌────────┐ + │ │M5 │ │Wait for│ + │ │Spindle ├──┤move & │ + └──┤Stop │ │disable │ + └──────────┘ └────────┘ + ┌──────────┐ ┌──────────┐ + Sensors─────┤Fault ├──┤Disable │ + └──────────┘ │power │ + └──────────┘ + +#### Laser Mode Logic: + + ┌──────────┐ ┌─────────────┐ ┌───────────┐ + │M3,M4,M5 I│ │Set power │ │Stepper │ + ┌──┤Standard ├──┤Immediately &├──┤processes │ + │ │Default │ │wait for move│ │moves │ + │ │ │ │completion │ │ │ + │ └──────────┘ └─────────────┘ └───────────┘ + │ ┌──────────┐ ┌───────────┐ ┌───────────┐ ┌────────────┐ ┌────────────┐ ┌────────────┐ ┌───────────┐ + ┌─────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ + │GCode│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ + │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ + └─────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ + │ └──────────┘ └───────────┘ └───────────┘ └────────────┘ └────────────┘ └────────────┘ └───────────┘ + │ ┌──────────┐ ┌───────────┐ ┌────────────────┐ ┌───────────┐ + │ │M4 I │ │Gx F-Value │ │Planner │ │Stepper │ + │ │Dynamic │ │set power │ │Calc & set block│ │uses block │ + └──┤Inline ├──┤or use ├──┤block power ├──┤values to │ + │ │ │default │ │using F-Value │ │apply power│ + └──────────┘ └───────────┘ └────────────────┘ └───────────┘ + ┌──────────┐ ┌──────────┐ + Sensors─────┤Fault ├──┤Disable │ + └──────────┘ │Power │ + └──────────┘ + + + +### Continuous Inline Trap Power Calculations + +When LASER_FEATURE and LASER_POWER_TRAP are defined, planner calculations are performed and applied to the incoming laser power S-Value. The power will be factored and distributed across trapezoid acceleration and deceleration movements. + +When the laser.power > 0 + +We set a minimum power if defined in SPEED_POWER_MIN it's fed into the planner block as laser_power_floor. + +A reduced entry laser power factor is based on the entry step rate to cruise step rate ratio for acceleration. + + block entry laser power = laser power * ( entry step rate / cruise step rate ) + +The initial power will be set to no less than the laser_power_floor or the inital power calculation. + +The reduced final power factor is based on the final step rate to cruise step rate ratio for deceleration. + + block exit laser power = laser power * ( exit step rate / cruise step rate ) + +Once the entry and exit power values are determined, the values are divided into step increments to be applied in the stepper. + + trap step power incr_decr = ( cruize power - entry_exit ) / accel_decel_steps + +The trap steps are incremented or decremented during each accel or decel step until the block is complete. +Step power is either cumulatively added or subtracted during trapeziod ramp progressions. + +#### Planner Code: + + ``` + if (block->laser.power > 0) { + NOLESS(block->laser.power, laser_power_floor); + block->laser.trap_ramp_active_pwr = (block->laser.power - laser_power_floor) * (initial_rate / float(block->nominal_rate)) + laser_power_floor; + block->laser.trap_ramp_entry_incr = (block->laser.power - block->laser.trap_ramp_active_pwr) / accelerate_steps; + float laser_pwr = block->laser.power * (final_rate / float(block->nominal_rate)); + NOLESS(laser_pwr, laser_power_floor); + block->laser.trap_ramp_exit_decr = (block->laser.power - laser_pwr) / decelerate_steps; + ``` + +#### Stepper Code: + + ``` + if (current_block->laser.trap_ramp_entry_incr > 0) { + cutter.apply_power(current_block->laser.trap_ramp_active_pwr); + current_block->laser.trap_ramp_active_pwr += current_block->laser.trap_ramp_entry_incr; + ``` + + ``` + if (current_block->laser.trap_ramp_exit_decr > 0) { + current_block->laser.trap_ramp_active_pwr -= current_block->laser.trap_ramp_exit_decr; + cutter.apply_power(current_block->laser.trap_ramp_active_pwr); + ``` + +### Dynamic Inline Calculations + +Dynamic mode will calculate laser power based on the F-Value feedrate. The method uses bit shifting to set a power level from 0 to 255. It's simple and fast and we can use a scaler to shift the laser power output to center on a given power level. + +#### Spindle/Laser Code: + +``` + // Dynamic mode rate calculation + static inline uint8_t calc_dynamic_power() { + if (feedrate_mm_m > 65535) return 255; // Too fast, go always on + uint16_t rate = uint16_t(feedrate_mm_m); // 16 bits from the G-code parser float input + rate >>= 8; // Take the G-code input e.g. F40000 and shift off the lower bits to get an OCR value from 1-255 + return uint8_t(rate); + } +``` diff --git a/ini/avr.ini b/ini/avr.ini index b13596afe119..5944f8158344 100644 --- a/ini/avr.ini +++ b/ini/avr.ini @@ -16,7 +16,7 @@ platform = atmelavr@~3.4 build_flags = ${common.build_flags} -Wl,--relax board_build.f_cpu = 16000000L -src_filter = ${common.default_src_filter} + +build_src_filter = ${common.default_src_filter} + # # ATmega2560 diff --git a/ini/due.ini b/ini/due.ini index 28b68383074d..c1e2375d7c5a 100644 --- a/ini/due.ini +++ b/ini/due.ini @@ -16,9 +16,9 @@ # - RADDS # [env:DUE] -platform = atmelsam -board = due -src_filter = ${common.default_src_filter} + + +platform = atmelsam +board = due +build_src_filter = ${common.default_src_filter} + + [env:DUE_USB] extends = env:DUE diff --git a/ini/esp32.ini b/ini/esp32.ini index 4ac6b96f5c3d..05b045f16e83 100644 --- a/ini/esp32.ini +++ b/ini/esp32.ini @@ -13,14 +13,14 @@ # Espressif ESP32 # [env:esp32] -platform = espressif32@2.1.0 -board = esp32dev -build_flags = ${common.build_flags} -DCORE_DEBUG_LEVEL=0 -src_filter = ${common.default_src_filter} + -lib_ignore = NativeEthernet -upload_speed = 500000 -monitor_speed = 250000 -#upload_port = marlinesp.local +platform = espressif32@2.1.0 +board = esp32dev +build_flags = ${common.build_flags} -DCORE_DEBUG_LEVEL=0 +build_src_filter = ${common.default_src_filter} + +lib_ignore = NativeEthernet +upload_speed = 500000 +monitor_speed = 250000 +#upload_port = marlinesp.local #board_build.flash_mode = qio [env:FYSETC_E4] diff --git a/ini/features.ini b/ini/features.ini index 1ee8f3d8955d..6fd8a7950bae 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -32,6 +32,7 @@ LIB_INTERNAL_MAX31865 = src_filter=+ NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.8.0 src_filter=+ I2C_AMMETER = peterus/INA226Lib@1.1.2 + src_filter=+ USES_LIQUIDCRYSTAL = LiquidCrystal=https://github.com/MarlinFirmware/New-LiquidCrystal/archive/1.5.1.zip USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 @@ -48,7 +49,6 @@ SPI_EEPROM = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ DWIN_LCD_PROUI = src_filter=+ -DWIN_CREALITY_LCD_JYERSUI = src_filter=+ IS_DWIN_MARLINUI = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ IS_TFTGLCD_PANEL = src_filter=+ @@ -236,7 +236,7 @@ HAS_SERVOS = src_filter=+ + HAS_MICROSTEPS = src_filter=+ (ESP3D_)?WIFISUPPORT = AsyncTCP, ESP Async WebServer - ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/master-2.0.7.zip + ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/master.zip arduinoWebSockets=links2004/WebSockets@2.3.4 luc-github/ESP32SSDP@^1.1.1 lib_ignore=ESPAsyncTCP diff --git a/ini/lpc176x.ini b/ini/lpc176x.ini index 95f5637a5dec..0cb26628fe49 100644 --- a/ini/lpc176x.ini +++ b/ini/lpc176x.ini @@ -20,7 +20,7 @@ lib_ldf_mode = off lib_compat_mode = strict extra_scripts = ${common.extra_scripts} Marlin/src/HAL/LPC1768/upload_extra_script.py -src_filter = ${common.default_src_filter} + + +build_src_filter = ${common.default_src_filter} + + lib_deps = ${common.lib_deps} Servo custom_marlin.USES_LIQUIDCRYSTAL = arduino-libraries/LiquidCrystal@~1.0.7 diff --git a/ini/native.ini b/ini/native.ini index 3d196f343649..693a985d4e92 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -13,14 +13,14 @@ # No supported Arduino libraries, base Marlin only # [env:linux_native] -platform = native -framework = -build_flags = -D__PLAT_LINUX__ -std=gnu++17 -ggdb -g -lrt -lpthread -D__MARLIN_FIRMWARE__ -Wno-expansion-to-defined -src_build_flags = -Wall -IMarlin/src/HAL/LINUX/include -build_unflags = -Wall -lib_ldf_mode = off -lib_deps = -src_filter = ${common.default_src_filter} + +platform = native +framework = +build_flags = -D__PLAT_LINUX__ -std=gnu++17 -ggdb -g -lrt -lpthread -D__MARLIN_FIRMWARE__ -Wno-expansion-to-defined +build_src_flags = -Wall -IMarlin/src/HAL/LINUX/include +build_unflags = -Wall +lib_ldf_mode = off +lib_deps = +build_src_filter = ${common.default_src_filter} + # # Native Simulation @@ -35,13 +35,13 @@ src_filter = ${common.default_src_filter} + platform = native framework = build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g -src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align +build_src_flags = -Wall -Wno-expansion-to-defined -Wcast-align release_flags = -g0 -O3 -flto debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off -src_filter = ${common.default_src_filter} + +build_src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/0.0.2.zip + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/refs/heads/bugfix-2.0.x.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip extra_scripts = ${common.extra_scripts} @@ -63,12 +63,12 @@ build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags} # # Simulator for macOS (MacPorts) # -# sudo port install gcc10 gdb glm libsdl2 libsdl2_net freetype +# sudo port install gcc11 gdb glm libsdl2 libsdl2_net freetype # sudo port install ld64 @3_3 +ld64_xcode # # cd /opt/local/bin # sudo rm -f gcc g++ cc -# sudo ln -s gcc-mp-10 gcc ; sudo ln -s g++-mp-10 g++ ; sudo ln -s g++ cc +# sudo ln -s gcc-mp-11 gcc ; sudo ln -s g++-mp-11 g++ ; sudo ln -s g++ cc # This step may be obsolete: # sudo port uninstall ld64 ld64-latest # @@ -78,8 +78,7 @@ build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags} # If Xcode is installed be sure to run `xcode-select --install` first. # [simulator_macos] -build_unflags = -lGL -custom_verbose = 0 +build_unflags = -lGL -fstack-protector-strong build_flags = -I/opt/local/include -I/opt/local/include/freetype2 @@ -88,16 +87,21 @@ build_flags = -Wl,-framework,OpenGl -Wl,-framework,CoreFoundation -lSDL2 + -fno-stack-protector [env:simulator_macos_debug] extends = env:simulator_linux_debug build_flags = ${env:simulator_linux_debug.build_flags} ${simulator_macos.build_flags} -ggdb -Og -D_THREAD_SAFE build_unflags = ${simulator_macos.build_unflags} +custom_verbose = 0 +custom_gcc = g++ [env:simulator_macos_release] extends = env:simulator_linux_release build_flags = ${env:simulator_linux_release.build_flags} ${simulator_macos.build_flags} build_unflags = ${simulator_macos.build_unflags} +custom_verbose = 0 +custom_gcc = g++ # # Simulator for Windows 10 @@ -107,6 +111,6 @@ build_unflags = ${simulator_macos.build_unflags} # [env:simulator_windows] extends = simulator_common -src_build_flags = ${simulator_common.src_build_flags} -fpermissive +build_src_flags = ${simulator_common.build_src_flags} -fpermissive build_flags = ${simulator_common.build_flags} ${simulator_common.debug_build_flags} -IC:\\msys64\\mingw64\\include\\SDL2 -fno-stack-protector -Wl,-subsystem,windows -ldl -lmingw32 -lSDL2main -lSDL2 -lSDL2_net -lopengl32 -lssp build_type = debug diff --git a/ini/renamed.ini b/ini/renamed.ini index b325476d2f9e..75f5dc3accc7 100644 --- a/ini/renamed.ini +++ b/ini/renamed.ini @@ -48,3 +48,11 @@ extends = renamed [env:STM32F103RC_btt_512K_USB_maple] # Renamed to STM32F103RE_btt_USB_maple extends = renamed + +[env:STM32F103RC_meeb] +# Renamed to STM32F103RC_meeb_maple +extends = renamed + +[env:STM32F103VE_GTM32] +# Renamed to STM32F103VE_GTM32_maple +extends = renamed diff --git a/ini/samd51.ini b/ini/samd51.ini index 34fcc84371c8..d7d9b3a4211c 100644 --- a/ini/samd51.ini +++ b/ini/samd51.ini @@ -13,14 +13,14 @@ # Adafruit Grand Central M4 (Atmel SAMD51P20A ARM Cortex-M4) # [env:SAMD51_grandcentral_m4] -platform = atmelsam -board = adafruit_grandcentral_m4 -build_flags = ${common.build_flags} -std=gnu++17 -build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + -lib_deps = ${common.lib_deps} - SoftwareSerialM -extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py +platform = atmelsam +board = adafruit_grandcentral_m4 +build_flags = ${common.build_flags} -std=gnu++17 +build_unflags = -std=gnu++11 +build_src_filter = ${common.default_src_filter} + +lib_deps = ${common.lib_deps} + SoftwareSerialM +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py custom_marlin.SDSUPPORT = SdFat - Adafruit Fork, Adafruit SPIFlash -debug_tool = jlink +debug_tool = jlink diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index 1d3f858bf8e9..c8f28cd0e314 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -18,7 +18,7 @@ build_flags = ${common.build_flags} -DTIM_IRQ_PRIO=13 -DADC_RESOLUTION=12 build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + + +build_src_filter = ${common.default_src_filter} + + extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py diff --git a/ini/stm32f0.ini b/ini/stm32f0.ini index d6251344c365..d62ac3acf54f 100644 --- a/ini/stm32f0.ini +++ b/ini/stm32f0.ini @@ -43,9 +43,9 @@ build_flags = ${common_stm32.build_flags} # Malyan M300 (STM32F070CB) # [env:malyan_M300] -extends = common_stm32 -board = malyanm300_f070cb -build_flags = ${common_stm32.build_flags} - -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB - -DHAL_UART_MODULE_ENABLED -src_filter = ${common.default_src_filter} + +extends = common_stm32 +board = malyanm300_f070cb +build_flags = ${common_stm32.build_flags} + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB + -DHAL_UART_MODULE_ENABLED +build_src_filter = ${common.default_src_filter} + diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 9ea848f1b6b1..18c861ba1ebe 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -22,64 +22,74 @@ # # HAL/STM32F1 Common Environment values # -[common_stm32f1] +[STM32F1_maple] platform = ststm32@~12.1 board_build.core = maple build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DARDUINO_ARCH_STM32 -DMAPLE_STM32F1 build_unflags = -std=gnu11 -std=gnu++11 -src_filter = ${common.default_src_filter} + +build_src_filter = ${common.default_src_filter} + lib_ignore = SPI, FreeRTOS701, FreeRTOS821 lib_deps = ${common.lib_deps} SoftwareSerialM platform_packages = tool-stm32duino extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py - pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py - buildroot/share/PlatformIO/scripts/offset_and_rename.py + pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py + pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py + buildroot/share/PlatformIO/scripts/custom_board.py + buildroot/share/PlatformIO/scripts/offset_and_rename.py # -# STM32F103RC +# Generic STM32F103RC environment +# +[env:STM32F103RC_maple] +extends = STM32F1_maple +board = genericSTM32F103RC +monitor_speed = 115200 + +# +# Generic STM32F103RE environment # -[common_STM32F103RC_maple] -extends = common_stm32f1 -board = genericSTM32F103RC -monitor_speed = 115200 +[env:STM32F103RE_maple] +extends = STM32F1_maple +board = genericSTM32F103RE +monitor_speed = 115200 # # MEEB_3DP (STM32F103RCT6 with 512K) # -[env:STM32F103RC_meeb] -extends = common_STM32F103RC_maple -board = marlin_MEEB_3DP -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 - -DSS_TIMER=4 - -DSTM32_FLASH_SIZE=512 - -DHSE_VALUE=12000000U - -DUSE_USB_COMPOSITE - -DVECT_TAB_OFFSET=0x2000 - -DGENERIC_BOOTLOADER -extra_scripts = ${common_stm32f1.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py - buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py -lib_deps = ${common_stm32f1.lib_deps} - USBComposite for STM32F1@0.91 +[env:STM32F103RC_meeb_maple] +extends = env:STM32F103RC_maple +board = marlin_maple_MEEB_3DP +build_flags = ${STM32F1_maple.build_flags} + -DDEBUG_LEVEL=0 + -DSS_TIMER=4 + -DSTM32_FLASH_SIZE=512 + -DHSE_VALUE=12000000U + -DUSE_USB_COMPOSITE + -DVECT_TAB_OFFSET=0x2000 + -DGENERIC_BOOTLOADER +board_build.ldscript = STM32F103RC_MEEB_3DP.ld +extra_scripts = ${STM32F1_maple.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py + buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +lib_deps = ${STM32F1_maple.lib_deps} + USBComposite for STM32F1@0.91 custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use -debug_tool = stlink -upload_protocol = dfu +debug_tool = stlink +upload_protocol = dfu # # FYSETC STM32F103RC # [env:STM32F103RC_fysetc_maple] -extends = common_STM32F103RC_maple -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py -build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -lib_ldf_mode = chain -debug_tool = stlink -upload_protocol = serial +extends = env:STM32F103RC_maple +extra_scripts = ${STM32F1_maple.extra_scripts} + buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +build_flags = ${STM32F1_maple.build_flags} -DDEBUG_LEVEL=0 +lib_ldf_mode = chain +debug_tool = stlink +upload_protocol = serial # # BigTree SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) @@ -88,48 +98,28 @@ upload_protocol = serial # STM32F103RC_btt_USB_maple ......... RCT6 with 256K (USB mass storage) # [env:STM32F103RC_btt_maple] -extends = common_STM32F103RC_maple +extends = env:STM32F103RC_maple board_build.address = 0x08007000 board_build.ldscript = STM32F103RC_SKR_MINI_256K.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 +build_flags = ${STM32F1_maple.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 monitor_speed = 115200 [env:STM32F103RC_btt_USB_maple] -extends = env:STM32F103RC_btt_maple -build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} - USBComposite for STM32F1@0.91 - -# -# Generic STM32F103RE environment -# -[env:STM32F103RE_maple] -extends = common_stm32f1 -board = genericSTM32F103RE -monitor_speed = 115200 - -# -# Generic STM32F103RC environment -# -[env:STM32F103RC_maple] -extends = common_stm32f1 -board = genericSTM32F103RC -monitor_speed = 115200 +extends = env:STM32F103RC_btt_maple +build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} + USBComposite for STM32F1@0.91 # # Creality (STM32F103RET6) # [env:STM32F103RE_creality_maple] extends = env:STM32F103RE_maple -build_flags = ${common_stm32f1.build_flags} -DTEMP_TIMER_CHAN=4 +build_flags = ${STM32F1_maple.build_flags} -DTEMP_TIMER_CHAN=4 board_build.address = 0x08007000 board_build.ldscript = creality.ld -extra_scripts = ${common_stm32f1.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py - buildroot/share/PlatformIO/scripts/custom_board.py +extra_scripts = ${STM32F1_maple.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/random-bin.py debug_tool = jlink upload_protocol = jlink @@ -138,15 +128,22 @@ upload_protocol = jlink # [env:STM32F103RC_creality_maple] extends = env:STM32F103RC_maple -build_flags = ${common_stm32f1.build_flags} -DTEMP_TIMER_CHAN=4 +build_flags = ${STM32F1_maple.build_flags} -DTEMP_TIMER_CHAN=4 board_build.address = 0x08007000 board_build.ldscript = creality.ld -extra_scripts = ${common_stm32f1.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py - buildroot/share/PlatformIO/scripts/custom_board.py +extra_scripts = ${STM32F1_maple.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/random-bin.py debug_tool = jlink upload_protocol = jlink +# +# Creality (STM32F103RET6) +# +[env:STM32F103RE_creality_smartPro_maple] +extends = env:STM32F103RE_creality_maple +board_build.address = 0x08010000 +board_build.ldscript = crealityPro.ld + # # BigTree SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # @@ -154,204 +151,197 @@ upload_protocol = jlink # STM32F103RE_btt_USB_maple ......... RET6 (USB mass storage) # [env:STM32F103RE_btt_maple] -extends = env:STM32F103RE_maple +extends = env:STM32F103RE_maple board_build.address = 0x08007000 board_build.ldscript = STM32F103RE_SKR_MINI_512K.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 -debug_tool = stlink -upload_protocol = stlink +build_flags = ${STM32F1_maple.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 +debug_tool = stlink +upload_protocol = stlink [env:STM32F103RE_btt_USB_maple] -extends = env:STM32F103RE_btt_maple -build_flags = ${env:STM32F103RE_btt_maple.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${common_stm32f1.lib_deps} - USBComposite for STM32F1@0.91 +extends = env:STM32F103RE_btt_maple +build_flags = ${env:STM32F103RE_btt_maple.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${STM32F1_maple.lib_deps} + USBComposite for STM32F1@0.91 # # Geeetech GTM32 (STM32F103VET6) # -[env:STM32F103VE_GTM32] -extends = common_stm32f1 +[env:STM32F103VE_GTM32_maple] +extends = STM32F1_maple board = genericSTM32F103VE -build_flags = ${common_stm32f1.build_flags} - -ffunction-sections -fdata-sections -nostdlib -MMD - -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DBOARD_generic_stm32f103v - -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 - -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +build_flags = ${STM32F1_maple.build_flags} + -ffunction-sections -fdata-sections -nostdlib -MMD + -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DBOARD_generic_stm32f103v + -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 + -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 upload_protocol = serial # # Longer 3D board in Alfawise U20 (STM32F103VET6) # [env:STM32F103VE_longer_maple] -extends = common_stm32f1 -board = genericSTM32F103VE +extends = STM32F1_maple +board = genericSTM32F103VE board_build.address = 0x08010000 board_build.rename = project.bin board_build.ldscript = STM32F103VE_longer.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 -build_unflags = ${common_stm32f1.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +build_flags = ${STM32F1_maple.build_flags} + -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 +build_unflags = ${STM32F1_maple.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 # # MKS Robin Mini (STM32F103VET6) # [env:mks_robin_mini_maple] -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_mini.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE +extends = STM32F1_maple +board = genericSTM32F103VE +board_build.address = 0x08007000 +board_build.rename = Robin_mini.bin +board_build.ldscript = mks_robin_mini.ld +build_flags = ${STM32F1_maple.build_flags} -DMCU_STM32F103VE # # MKS Robin Nano (STM32F103VET6) # [env:mks_robin_nano35_maple] -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_nano35.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSS_TIMER=4 -debug_tool = jlink -upload_protocol = jlink +extends = STM32F1_maple +board = genericSTM32F103VE +board_build.address = 0x08007000 +board_build.rename = Robin_nano35.bin +board_build.ldscript = mks_robin_nano.ld +build_flags = ${STM32F1_maple.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 +debug_tool = jlink +upload_protocol = jlink # # MKS Robin (STM32F103ZET6) # [env:mks_robin_maple] -extends = common_stm32f1 -board = genericSTM32F103ZE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin.py -build_flags = ${common_stm32f1.build_flags} - -DSS_TIMER=4 -DSTM32_XL_DENSITY +extends = STM32F1_maple +board = genericSTM32F103ZE +board_build.address = 0x08007000 +board_build.rename = Robin.bin +board_build.ldscript = mks_robin.ld +build_flags = ${STM32F1_maple.build_flags} -DSS_TIMER=4 -DSTM32_XL_DENSITY # # MKS Robin Pro (STM32F103ZET6) # [env:mks_robin_pro_maple] -extends = env:mks_robin_maple -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_pro.py +extends = env:mks_robin_maple +board_build.address = 0x08007000 +board_build.rename = Robin_pro.bin +board_build.ldscript = mks_robin_pro.ld # # TRIGORILLA PRO (STM32F103ZET6) # [env:trigorilla_pro_maple] extends = env:mks_robin_maple -extra_scripts = ${common_stm32f1.extra_scripts} +extra_scripts = ${STM32F1_maple.extra_scripts} # # MKS Robin E3D (STM32F103RCT6) and # MKS Robin E3 with TMC2209 # [env:mks_robin_e3_maple] -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_e3.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 +extends = STM32F1_maple +board = genericSTM32F103RC +board_build.address = 0x08005000 +board_build.rename = Robin_e3.bin +board_build.ldscript = mks_robin_e3.ld +build_flags = ${STM32F1_maple.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 # # MKS Robin E3p (STM32F103VET6) # - LVGL UI # [env:mks_robin_e3p_maple] -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_e3p.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSS_TIMER=4 -debug_tool = jlink -upload_protocol = jlink +extends = STM32F1_maple +board = genericSTM32F103VE +board_build.address = 0x08007000 +board_build.rename = Robin_e3p.bin +board_build.ldscript = mks_robin_e3p.ld +build_flags = ${STM32F1_maple.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 +debug_tool = jlink +upload_protocol = jlink # # MKS Robin Lite/Lite2 (STM32F103RCT6) # [env:mks_robin_lite_maple] -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_lite.py +extends = STM32F1_maple +board = genericSTM32F103RC +board_build.address = 0x08005000 +board_build.rename = mksLite.bin +board_build.ldscript = mks_robin_lite.ld # # MKS ROBIN LITE3 (STM32F103RCT6) # [env:mks_robin_lite3_maple] -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_lite3.py +extends = STM32F1_maple +board = genericSTM32F103RC +board_build.address = 0x08005000 +board_build.rename = mksLite3.bin +board_build.ldscript = mks_robin_lite.ld # # JGAurora A5S A1 (STM32F103ZET6) # [env:jgaurora_a5s_a1_maple] -extends = common_stm32f1 -board = genericSTM32F103ZE +extends = STM32F1_maple +board = genericSTM32F103ZE board_build.address = 0x0800A000 board_build.ldscript = jgaurora_a5s_a1.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py - buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py -build_flags = ${common_stm32f1.build_flags} - -DSTM32F1xx -DSTM32_XL_DENSITY +extra_scripts = ${STM32F1_maple.extra_scripts} + buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +build_flags = ${STM32F1_maple.build_flags} -DSTM32F1xx -DSTM32_XL_DENSITY # # Malyan M200 (STM32F103CB) # [env:STM32F103CB_malyan_maple] -extends = common_stm32f1 -board = marlin_malyanM200 -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103CB -D__STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections - -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ -lib_ignore = ${common_stm32f1.lib_ignore} - SoftwareSerialM +extends = STM32F1_maple +board = marlin_malyanM200 +build_flags = ${STM32F1_maple.build_flags} + -DMCU_STM32F103CB -D__STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections + -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ +lib_ignore = ${STM32F1_maple.lib_ignore} + SoftwareSerialM # # Chitu boards like Tronxy X5s (STM32F103ZET6) # [env:chitu_f103_maple] -extends = common_stm32f1 -board = marlin_CHITU_F103 -extra_scripts = ${common_stm32f1.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py - buildroot/share/PlatformIO/scripts/chitu_crypt.py -build_flags = ${common_stm32f1.build_flags} - -DSTM32F1xx -DSTM32_XL_DENSITY -build_unflags = ${common_stm32f1.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +extends = STM32F1_maple +board = marlin_maple_CHITU_F103 +extra_scripts = ${STM32F1_maple.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py + buildroot/share/PlatformIO/scripts/chitu_crypt.py +build_flags = ${STM32F1_maple.build_flags} -DSTM32F1xx -DSTM32_XL_DENSITY +build_unflags = ${STM32F1_maple.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 # # Some Chitu V5 boards have a problem with GPIO init. # Use this target if G28 or G29 are always failing. # [env:chitu_v5_gpio_init_maple] -extends = env:chitu_f103_maple -build_flags = ${env:chitu_f103_maple.build_flags} -DCHITU_V5_Z_MIN_BUGFIX +extends = env:chitu_f103_maple +build_flags = ${env:chitu_f103_maple.build_flags} -DCHITU_V5_Z_MIN_BUGFIX # # FLYmaker FLY Mini (STM32F103RCT6) # [env:FLY_MINI_maple] -extends = common_stm32f1 -board = genericSTM32F103RC +extends = STM32F1_maple +board = genericSTM32F103RC board_build.address = 0x08005000 board_build.ldscript = fly_mini.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 +build_flags = ${STM32F1_maple.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 # # Zonestar ZM3E2 V1.0 / ZM3E4 V1.0 / ZM3E4 V2.0 @@ -361,18 +351,15 @@ build_flags = ${common_stm32f1.build_flags} # STM32F103VE_ZM3E4V2_USB_maple ......... VET6 with 512K # [ZONESTAR_ZM3E_maple] -extends = common_stm32f1 +extends = STM32F1_maple platform_packages = tool-stm32duino board_build.address = 0x08005000 board_build.offset = 0x5000 board_upload.maximum_size = 237568 -extra_scripts = ${common.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py - buildroot/share/PlatformIO/scripts/offset_and_rename.py -build_flags = ${common_stm32f1.build_flags} - -D__STM32F1__=1 -DDEBUG_LEVEL=0 -DSS_TIMER=4 -DSERIAL_USB -lib_deps = ${common_stm32f1.lib_deps} - USBComposite for STM32F1@0.91 +build_flags = ${STM32F1_maple.build_flags} + -D__STM32F1__=1 -DDEBUG_LEVEL=0 -DSS_TIMER=4 -DSERIAL_USB +lib_deps = ${STM32F1_maple.lib_deps} + USBComposite for STM32F1@0.91 lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, TMCStepper [env:STM32F103RC_ZM3E2_USB_maple] @@ -387,26 +374,24 @@ board_build.ldscript = ZONESTAR_ZM3E_256K.ld build_flags = ${ZONESTAR_ZM3E_maple.build_flags} -DTONE_TIMER=1 -DTONE_CHANNEL=2 [env:STM32F103VE_ZM3E4V2_USB_maple] -extends = ZONESTAR_ZM3E_maple -board = genericSTM32F103VE -board_build.ldscript = ZONESTAR_ZM3E_512K.ld -build_flags = ${ZONESTAR_ZM3E_maple.build_flags} -DTONE_TIMER=1 -DTONE_CHANNEL=2 +extends = ZONESTAR_ZM3E_maple +board = genericSTM32F103VE +board_build.ldscript = ZONESTAR_ZM3E_512K.ld +build_flags = ${ZONESTAR_ZM3E_maple.build_flags} -DTONE_TIMER=1 -DTONE_CHANNEL=2 board_upload.maximum_size = 499712 # # ERYONE ERY32 Mini (STM32F103VET6) # [env:ERYONE_ERY32_MINI_maple] -extends = common_stm32f1 +extends = STM32F1_maple board = genericSTM32F103VE -build_flags = ${common_stm32f1.build_flags} - -ffunction-sections -fdata-sections -nostdlib -MMD - -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 - -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 - -DSS_TIMER=4 +build_flags = ${STM32F1_maple.build_flags} + -ffunction-sections -fdata-sections -nostdlib -MMD + -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 + -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 + -DSS_TIMER=4 board_build.variant = MARLIN_F103Vx board_build.ldscript = eryone_ery32_mini.ld board_build.address = 0x08004000 -build_unflags = ${common_stm32f1.build_unflags} -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py +build_unflags = ${STM32F1_maple.build_unflags} diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 9002f81a8143..8dc9bc3061b8 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -89,22 +89,22 @@ board_upload.offset_address = 0x08005000 # Uses HAL STM32 to support Marlin UI for TFT screen with optional touch panel # [env:mks_robin] -extends = stm32_variant -board = genericSTM32F103ZE -board_build.variant = MARLIN_F103Zx -board_build.encrypt = Robin.bin -board_build.offset = 0x7000 -build_flags = ${stm32_variant.build_flags} - -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 -build_unflags = ${stm32_variant.build_unflags} - -DUSBCON -DUSBD_USE_CDC +extends = stm32_variant +board = genericSTM32F103ZE +board_build.variant = MARLIN_F103Zx +board_build.encrypt_mks = Robin.bin +board_build.offset = 0x7000 +build_flags = ${stm32_variant.build_flags} + -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC # # MKS Robin E3/E3D (STM32F103RCT6) with TMC2209 # [env:mks_robin_e3] extends = common_STM32F103RC_variant -board_build.encrypt = Robin_e3.bin +board_build.encrypt_mks = Robin_e3.bin board_build.offset = 0x5000 board_upload.offset_address = 0x08005000 build_flags = ${common_STM32F103RC_variant.build_flags} @@ -138,6 +138,7 @@ upload_protocol = jlink # [STM32F103Rx_creality_xfer] extends = STM32F103Rx_creality +build_flags = ${STM32F103Rx_creality.build_flags} -DXFER_BUILD extra_scripts = ${STM32F103Rx_creality.extra_scripts} pre:buildroot/share/scripts/upload.py upload_protocol = custom @@ -153,6 +154,11 @@ board = genericSTM32F103RE extends = STM32F103Rx_creality_xfer board = genericSTM32F103RE +[env:STM32F103RE_creality_smartPro] +extends = STM32F103Rx_creality +board_build.offset = 0x10000 +board_upload.offset_address = 0x08010000 + # # Creality 256K (STM32F103RC) # @@ -200,7 +206,7 @@ build_unflags = ${stm32_variant.build_unflags} -DUSBD_USE_CDC extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx -board_build.encrypt = Robin_mini.bin +board_build.encrypt_mks = Robin_mini.bin board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 build_flags = ${stm32_variant.build_flags} @@ -216,7 +222,7 @@ build_unflags = ${stm32_variant.build_unflags} extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx -board_build.encrypt = Robin_nano35.bin +board_build.encrypt_mks = Robin_nano35.bin board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 build_flags = ${stm32_variant.build_flags} @@ -244,12 +250,12 @@ build_unflags = ${stm32_variant.build_unflags} # Malyan M200 (STM32F103CB) # [env:STM32F103CB_malyan] -extends = common_stm32 -board = malyanm200_f103cb -build_flags = ${common_stm32.build_flags} - -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB - -DHAL_UART_MODULE_ENABLED -src_filter = ${common.default_src_filter} + +extends = common_stm32 +board = malyanm200_f103cb +build_flags = ${common_stm32.build_flags} + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB + -DHAL_UART_MODULE_ENABLED +build_src_filter = ${common.default_src_filter} + # # FLYmaker FLY Mini (STM32F103RCT6) @@ -269,7 +275,7 @@ build_flags = ${stm32_variant.build_flags} -DSS_TIMER=4 extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx -board_build.encrypt = Robin_mini.bin +board_build.encrypt_mks = Robin_mini.bin board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 build_flags = ${stm32_variant.build_flags} @@ -282,7 +288,7 @@ build_flags = ${stm32_variant.build_flags} extends = stm32_variant board = genericSTM32F103RC board_build.variant = MARLIN_F103Rx -board_build.encrypt = mksLite.bin +board_build.encrypt_mks = mksLite.bin board_build.offset = 0x5000 board_upload.offset_address = 0x08005000 @@ -291,14 +297,14 @@ board_upload.offset_address = 0x08005000 # [env:mks_robin_lite3] extends = env:mks_robin_lite -board_build.encrypt = mksLite3.bin +board_build.encrypt_mks = mksLite3.bin # # MKS Robin Pro (STM32F103ZET6) # [env:mks_robin_pro] -extends = env:mks_robin -board_build.encrypt = Robin_pro.bin +extends = env:mks_robin +board_build.encrypt_mks = Robin_pro.bin # # MKS Robin E3p (STM32F103VET6) @@ -308,7 +314,7 @@ board_build.encrypt = Robin_pro.bin extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx -board_build.encrypt = Robin_e3p.bin +board_build.encrypt_mks = Robin_e3p.bin board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 build_flags = ${stm32_variant.build_flags} @@ -325,7 +331,6 @@ extends = stm32_variant board = genericSTM32F103ZE board_build.variant = MARLIN_F103Zx board_build.offset = 0xA000 -board_build.rename = firmware_for_sd_upload.bin board_upload.offset_address = 0x0800A000 build_flags = ${stm32_variant.build_flags} -DSTM32F1xx -DSTM32_XL_DENSITY diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 437dbdcd9be1..ddb944e80f61 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -94,11 +94,11 @@ build_flags = ${stm32_variant.build_flags} -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS # -# STM32F407VET6 Index Mobo Rev 03 +# STM32F407VET6 Opulo Lumen REV3 # -[env:Index_Mobo_Rev03] +[env:Opulo_Lumen_REV3] extends = stm32_variant -board = marlin_index_mobo_rev03 +board = marlin_opulo_lumen_rev3 build_flags = ${stm32_variant.build_flags} -DARDUINO_BLACK_F407VE -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS @@ -106,24 +106,34 @@ extra_scripts = ${stm32_variant.extra_scripts} # # Anet ET4-MB_V1.x/ET4P-MB_V1.x (STM32F407VGT6 ARM Cortex-M4) -# For use with with davidtgbe's OpenBLT bootloader https://github.com/davidtgbe/openblt/releases -# Comment out board_build.offset = 0x10000 if you don't plan to use OpenBLT/flashing directly to 0x08000000. # -[env:Anet_ET4_OpenBLT] +[Anet_ET4] extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx -board_build.encrypt = firmware.srec -board_build.offset = 0x10000 -board_upload.offset_address = 0x08010000 build_flags = ${stm32_variant.build_flags} -DHAL_SD_MODULE_ENABLED -DHAL_SRAM_MODULE_ENABLED build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 + +# +# Anet ET4 directly flashed via ST-Link +# +[env:Anet_ET4_no_bootloader] +extends = Anet_ET4 +debug_tool = stlink +upload_protocol = stlink + +# +# Anet ET4 with OpenBLT from https://github.com/davidtgbe/openblt/releases +# +[env:Anet_ET4_OpenBLT] +extends = Anet_ET4 +board_build.encode = firmware.srec +board_build.offset = 0x10000 +board_upload.offset_address = 0x08010000 extra_scripts = ${stm32_variant.extra_scripts} buildroot/share/PlatformIO/scripts/openblt.py -debug_tool = jlink -upload_protocol = jlink # # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) @@ -251,11 +261,14 @@ build_unflags = ${env:BIGTREE_SKR_2_F429_USB.build_unflags} -Os -NDEBUG # BigTreeTech Octopus V1.0/1.1 / Octopus Pro V1.0 (STM32F446ZET6 ARM Cortex-M4) # [env:BIGTREE_OCTOPUS_V1] -extends = stm32_variant -board = marlin_BigTree_Octopus_v1 -board_build.offset = 0x8000 -build_flags = ${stm32_variant.build_flags} - -DSTM32F446_5VX -DUSE_USB_HS_IN_FS +extends = stm32_variant +board = marlin_BigTree_Octopus_v1 +board_build.offset = 0x8000 +board_upload.offset_address = 0x08008000 +debug_tool = stlink +upload_protocol = stlink +build_flags = ${stm32_variant.build_flags} + -DSTM32F446_5VX -DUSE_USB_HS_IN_FS # # BigTreeTech Octopus V1.0/1.1 / Octopus Pro V1.0 (STM32F446ZET6 ARM Cortex-M4) with USB Flash Drive Support @@ -274,11 +287,14 @@ build_flags = ${stm_flash_drive.build_flags} # BigTreeTech Octopus Pro V1.0 (STM32F429ZGT6 ARM Cortex-M4) # [env:BIGTREE_OCTOPUS_PRO_V1_F429] -extends = stm32_variant -board = marlin_BigTree_Octopus_Pro_v1_F429 -board_build.offset = 0x8000 -build_flags = ${stm32_variant.build_flags} - -DUSE_USB_HS_IN_FS +extends = stm32_variant +board = marlin_BigTree_Octopus_Pro_v1_F429 +board_build.offset = 0x8000 +board_upload.offset_address = 0x08008000 +debug_tool = stlink +upload_protocol = stlink +build_flags = ${stm32_variant.build_flags} + -DUSE_USB_HS_IN_FS # # BigTreeTech Octopus Pro V1.0 (STM32F429ZGT6 ARM Cortex-M4) with USB Flash Drive Support @@ -296,24 +312,24 @@ build_flags = ${stm_flash_drive.build_flags} # Lerdge base # [lerdge_common] -extends = stm32_variant -board = marlin_STM32F407ZGT6 -board_build.variant = MARLIN_LERDGE -board_build.offset = 0x10000 -build_flags = ${stm32_variant.build_flags} - -DSTM32F4 -DSTM32F4xx -DTARGET_STM32F4 - -DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 -DLERDGE_TFT35 -build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -extra_scripts = ${common_stm32.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py - buildroot/share/PlatformIO/scripts/lerdge.py +extends = stm32_variant +board = marlin_STM32F407ZGT6 +board_build.variant = MARLIN_LERDGE +board_build.crypt_lerdge = firmware.bin +board_build.offset = 0x10000 +build_flags = ${stm32_variant.build_flags} + -DSTM32F4 -DSTM32F4xx -DTARGET_STM32F4 + -DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 -DLERDGE_TFT35 +build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 +extra_scripts = ${stm32_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/lerdge.py # # Lerdge X (STM32F407VE) # [env:LERDGEX] -extends = lerdge_common -board_build.encrypt = Lerdge_X_firmware_force.bin +extends = lerdge_common +board_build.crypt_lerdge = Lerdge_X_firmware_force.bin # # Lerdge X with USB Flash Drive Support @@ -327,8 +343,8 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # Lerdge S (STM32F407ZG) # [env:LERDGES] -extends = lerdge_common -board_build.encrypt = Lerdge_firmware_force.bin +extends = lerdge_common +board_build.crypt_lerdge = Lerdge_firmware_force.bin # # Lerdge S with USB Flash Drive Support @@ -342,9 +358,9 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # Lerdge K (STM32F407ZG) # [env:LERDGEK] -extends = lerdge_common -board_build.encrypt = Lerdge_K_firmware_force.bin -build_flags = ${lerdge_common.build_flags} -DLERDGEK +extends = lerdge_common +board_build.crypt_lerdge = Lerdge_K_firmware_force.bin +build_flags = ${lerdge_common.build_flags} -DLERDGEK # # Lerdge K with USB Flash Drive Support @@ -358,17 +374,17 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # RUMBA32 # [env:rumba32] -extends = stm32_variant -board = rumba32_f446ve -board_build.variant = MARLIN_F446VE -board_build.offset = 0x0000 -build_flags = ${stm32_variant.build_flags} - -Os -DHAL_PCD_MODULE_ENABLED - -DDISABLE_GENERIC_SERIALUSB - -DHAL_UART_MODULE_ENABLED - -DTIMER_SERIAL=TIM9 -monitor_speed = 500000 -upload_protocol = dfu +extends = stm32_variant +board = rumba32_f446ve +board_build.variant = MARLIN_F446VE +board_build.offset = 0x0000 +build_flags = ${stm32_variant.build_flags} + -Os -DHAL_PCD_MODULE_ENABLED + -DDISABLE_GENERIC_SERIALUSB + -DHAL_UART_MODULE_ENABLED + -DTIMER_SERIAL=TIM9 +monitor_speed = 500000 +upload_protocol = dfu # # MKS Robin Pro V2 @@ -540,18 +556,30 @@ build_unflags = -DUSBD_USE_CDC # # TH3D EZBoard v2.0 (STM32F405RGT6 ARM Cortex-M4) # -[env:TH3D_EZBoard_V2] -extends = stm32_variant -board = genericSTM32F405RG -board_build.variant = MARLIN_TH3D_EZBOARD_V2 -board_build.encrypt = firmware.bin -board_build.offset = 0xC000 +[TH3D_EZBoard_V2] +extends = stm32_variant +board = genericSTM32F405RG +board_build.variant = MARLIN_TH3D_EZBOARD_V2 +build_flags = ${stm32_variant.build_flags} -DHSE_VALUE=12000000U -O0 + +# +# TH3D EZBoard v2.0 directly flashed via ST-Link +# +[env:TH3D_EZBoard_V2_no_bootloader] +extends = TH3D_EZBoard_V2 +debug_tool = stlink +upload_protocol = stlink + +# +# TH3D EZBoard v2.0 with OpenBLT from https://github.com/rhapsodyv/OpenBLT-STM32 +# +[env:TH3D_EZBoard_V2_OpenBLT] +extends = TH3D_EZBoard_V2 +board_build.encode = firmware.bin +board_build.offset = 0xC000 board_upload.offset_address = 0x0800C000 -build_flags = ${stm32_variant.build_flags} -DHSE_VALUE=12000000U -O0 -debug_tool = stlink -upload_protocol = stlink -extra_scripts = ${stm32_variant.extra_scripts} - buildroot/share/PlatformIO/scripts/openblt.py +extra_scripts = ${stm32_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/openblt.py # # BOARD_MKS_ROBIN_NANO_V1_3_F4 @@ -588,4 +616,31 @@ build_flags = ${common_stm32.build_flags} -DUSB_PRODUCT=\"Artillery_3D_Printer\" -DFLASH_DATA_SECTOR=1U -DFLASH_BASE_ADDRESS=0x08004000 extra_scripts = ${common_stm32.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + +# +# Ender-3 S1 STM32F401RC_creality +# +[env:STM32F401RC_creality] +extends = stm32_variant +board = genericSTM32F401RC +board_build.variant = MARLIN_CREALITY_STM32F401RC +board_build.offset = 0x10000 +board_upload.offset_address = 0x08010000 +build_flags = ${stm32_variant.build_flags} -DMCU_STM32F401RC -DSTM32F4 + -DSS_TIMER=4 -DTIMER_SERVO=TIM5 + -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC +extra_scripts = ${stm32_variant.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/random-bin.py +monitor_speed = 115200 + +[env:STM32F401RC_creality_jlink] +extends = env:STM32F401RC_creality +debug_tool = jlink +upload_protocol = jlink + +[env:STM32F401RC_creality_stlink] +extends = env:STM32F401RC_creality +debug_tool = stlink +upload_protocol = stlink diff --git a/ini/stm32g0.ini b/ini/stm32g0.ini index e6094c1e312d..b6074d3af8d0 100644 --- a/ini/stm32g0.ini +++ b/ini/stm32g0.ini @@ -36,3 +36,13 @@ build_flags = ${stm32_variant.build_flags} -DSTEP_TIMER_IRQ_PRIO=0 upload_protocol = stlink debug_tool = stlink + +# +# Custom upload to SD via Marlin with Binary Protocol +# +[env:STM32G0B1RE_btt_xfer] +extends = env:STM32G0B1RE_btt +build_flags = ${env:STM32G0B1RE_btt.build_flags} -DXFER_BUILD +extra_scripts = ${env:STM32G0B1RE_btt.extra_scripts} + pre:buildroot/share/scripts/upload.py +upload_protocol = custom diff --git a/ini/stm32h7.ini b/ini/stm32h7.ini index b0cb10866c55..fb898d1b72b1 100644 --- a/ini/stm32h7.ini +++ b/ini/stm32h7.ini @@ -20,7 +20,7 @@ ################################# # -# BigTreeTech SKR SE BX (STM32H743IIT6 ARM Cortex-M7) +# BigTreeTech SKR SE BX V2.0 / V3.0 (STM32H743IIT6 ARM Cortex-M7) # [env:BTT_SKR_SE_BX] extends = stm32_variant @@ -38,3 +38,24 @@ build_flags = ${stm32_variant.build_flags} ${stm_flash_drive.build_flags} -DHAL_SD_MODULE_ENABLED upload_protocol = cmsis-dap debug_tool = cmsis-dap + +# +# BigTreeTech SKR V3.0 / V3.0 EZ (STM32H743VIT6 ARM Cortex-M7) +# +[env:STM32H743Vx_btt] +extends = stm32_variant +platform = ststm32@~14.1.0 +platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/main.zip +board = marlin_STM32H743Vx +board_build.offset = 0x20000 +board_upload.offset_address = 0x08020000 +build_flags = ${stm32_variant.build_flags} + -DPIN_SERIAL1_RX=PA_10 -DPIN_SERIAL1_TX=PA_9 + -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 + -DPIN_SERIAL4_RX=PA_1 -DPIN_SERIAL4_TX=PA_0 + -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 + -DTIMER_SERVO=TIM5 -DTIMER_TONE=TIM2 + -DSTEP_TIMER_IRQ_PRIO=0 + -DD_CACHE_DISABLED +upload_protocol = cmsis-dap +debug_tool = cmsis-dap diff --git a/ini/teensy.ini b/ini/teensy.ini index ab0617b5b7b5..dac4b40c3053 100644 --- a/ini/teensy.ini +++ b/ini/teensy.ini @@ -45,36 +45,36 @@ board = teensy2pp # Teensy 3.x - 4.x # [teensy_arm] -platform = teensy@~4.12.0 -src_filter = ${common.default_src_filter} -lib_ignore = NativeEthernet +platform = teensy@~4.12.0 +build_src_filter = ${common.default_src_filter} +lib_ignore = NativeEthernet # # Teensy 3.1 / 3.2 (ARM Cortex-M4) # [env:teensy31] -extends = teensy_arm -board = teensy31 -src_filter = ${teensy_arm.src_filter} + +extends = teensy_arm +board = teensy31 +build_src_filter = ${teensy_arm.build_src_filter} + # # Teensy 3.5 / 3.6 (ARM Cortex-M4) # [env:teensy35] -extends = teensy_arm -board = teensy35 -src_filter = ${teensy_arm.src_filter} + +extends = teensy_arm +board = teensy35 +build_src_filter = ${teensy_arm.build_src_filter} + [env:teensy36] -extends = teensy_arm -board = teensy36 -src_filter = ${teensy_arm.src_filter} + +extends = teensy_arm +board = teensy36 +build_src_filter = ${teensy_arm.build_src_filter} + # # Teensy 4.0 / 4.1 (ARM Cortex-M7) # [env:teensy41] -extends = teensy_arm -board = teensy41 -src_filter = ${teensy_arm.src_filter} + -lib_ignore = +extends = teensy_arm +board = teensy41 +build_src_filter = ${teensy_arm.build_src_filter} + +lib_ignore = diff --git a/platformio.ini b/platformio.ini index ac52fd7a1f47..3820e7019389 100644 --- a/platformio.ini +++ b/platformio.ini @@ -96,6 +96,7 @@ default_src_filter = + - - + - - - - + - - - - - @@ -262,12 +263,13 @@ default_src_filter = + - - + # Default values apply to all 'env:' prefixed environments # [env] -framework = arduino -extra_scripts = ${common.extra_scripts} -build_flags = ${common.build_flags} -lib_deps = ${common.lib_deps} -monitor_speed = 250000 -monitor_flags = +framework = arduino +extra_scripts = ${common.extra_scripts} +build_flags = ${common.build_flags} +lib_deps = ${common.lib_deps} +platform_packages = platformio/tool-dfuutil@^1.11.0 +monitor_speed = 250000 +monitor_flags = --quiet --echo --eol @@ -281,7 +283,7 @@ monitor_flags = # Just print the dependency tree # [env:include_tree] -platform = atmelavr -board = megaatmega2560 -build_flags = -c -H -std=gnu++11 -Wall -Os -D__MARLIN_FIRMWARE__ -src_filter = + +platform = atmelavr +board = megaatmega2560 +build_flags = -c -H -std=gnu++11 -Wall -Os -D__MARLIN_FIRMWARE__ +build_src_filter = +