diff --git a/.aiderignore b/.aiderignore new file mode 100644 index 0000000000..b80c459446 --- /dev/null +++ b/.aiderignore @@ -0,0 +1,21 @@ +# Build artifacts +buildroot/ +*.o +*.a +*.so +*.dylib +*.dll +*.exe + +# Web assets +*.min.js +*.min.css + +# Generated files +__pycache__/ +*.pyc +.DS_Store + +# IDE files +.vscode/ +.idea/ diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile new file mode 100644 index 0000000000..4f29a10053 --- /dev/null +++ b/.devcontainer/Dockerfile @@ -0,0 +1,29 @@ +# See here for image contents: https://github.com/microsoft/vscode-dev-containers/tree/v0.187.0/containers/python-3/.devcontainer/base.Dockerfile + +# [Choice] Python version: 3, 3.9, 3.8, 3.7, 3.6 +ARG VARIANT="3.9.0-buster" +FROM python:${VARIANT} + +# [Option] Install Node.js +ARG INSTALL_NODE="true" +ARG NODE_VERSION="lts/*" +RUN if [ "${INSTALL_NODE}" = "true" ]; then su vscode -c "umask 0002 && . /usr/local/share/nvm/nvm.sh && nvm install ${NODE_VERSION} 2>&1"; fi + +# [Optional] If your pip requirements rarely change, uncomment this section to add them to the image. +# COPY requirements.txt /tmp/pip-tmp/ +# RUN pip3 --disable-pip-version-check --no-cache-dir install -r /tmp/pip-tmp/requirements.txt \ +# && rm -rf /tmp/pip-tmp + +# [Optional] Uncomment this section to install additional OS packages. +# RUN apt-get update && export DEBIAN_FRONTEND=noninteractive \ +# && apt-get -y install --no-install-recommends + +# [Optional] Uncomment this line to install global node packages. +# RUN su vscode -c "source /usr/local/share/nvm/nvm.sh && npm install -g " 2>&1 + + +RUN pip install -U https://github.com/platformio/platformio-core/archive/develop.zip +RUN platformio update +# To get the test platforms +RUN pip install PyYaml +#ENV PATH /code/buildroot/bin/:/code/buildroot/tests/:${PATH} diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json new file mode 100644 index 0000000000..96d6af1932 --- /dev/null +++ b/.devcontainer/devcontainer.json @@ -0,0 +1,51 @@ +// For format details, see https://aka.ms/devcontainer.json. For config options, see the README at: +// https://github.com/microsoft/vscode-dev-containers/tree/v0.187.0/containers/python-3 +{ + "name": "Python 3", + "build": { + "dockerfile": "Dockerfile", + "context": "..", + "args": { + // Update 'VARIANT' to pick a Python version: 3, 3.6, 3.7, 3.8, 3.9 + "VARIANT": "3.9.0-buster", + // Options + "INSTALL_NODE": "false", + "NODE_VERSION": "lts/*" + } + }, + + // Set *default* container specific settings.json values on container create. + "settings": { + "python.pythonPath": "/usr/local/bin/python", + "python.languageServer": "Pylance", + "python.linting.enabled": true, + "python.linting.pylintEnabled": true, + "python.formatting.autopep8Path": "/usr/local/py-utils/bin/autopep8", + "python.formatting.blackPath": "/usr/local/py-utils/bin/black", + "python.formatting.yapfPath": "/usr/local/py-utils/bin/yapf", + "python.linting.banditPath": "/usr/local/py-utils/bin/bandit", + "python.linting.flake8Path": "/usr/local/py-utils/bin/flake8", + "python.linting.mypyPath": "/usr/local/py-utils/bin/mypy", + "python.linting.pycodestylePath": "/usr/local/py-utils/bin/pycodestyle", + "python.linting.pydocstylePath": "/usr/local/py-utils/bin/pydocstyle", + "python.linting.pylintPath": "/usr/local/py-utils/bin/pylint" + }, + + // Add the IDs of extensions you want installed when the container is created. + "extensions": [ + "ms-python.python", + "ms-python.vscode-pylance", + "platformio.platformio-ide", + "marlinfirmware.auto-build", + "editorconfig.editorconfig" + ] + + // Use 'forwardPorts' to make a list of ports inside the container available locally. + // , "forwardPorts": [] + + // Use 'postCreateCommand' to run commands after the container is created. + // , "postCreateCommand": "pip3 install --user -r requirements.txt" + + // Comment out connect as root instead. More info: https://aka.ms/vscode-remote/containers/non-root. + // , "remoteUser": "vscode" +} diff --git a/.editorconfig b/.editorconfig index b8f6ef7f8e..1037e74ef3 100644 --- a/.editorconfig +++ b/.editorconfig @@ -1,19 +1,33 @@ # editorconfig.org root = true +[*] +trim_trailing_whitespace = true +insert_final_newline = true + [{*.patch,syntax_test_*}] trim_trailing_whitespace = false +[{*.c,*.cpp,*.h,*.ino,*.py,Makefile}] +end_of_line = lf + [{*.c,*.cpp,*.h,*.ino}] charset = utf-8 - -[{*.c,*.cpp,*.h,*.ino,Makefile}] -trim_trailing_whitespace = true -insert_final_newline = true -end_of_line = lf indent_style = space indent_size = 2 -[{*.py,*.conf,*.sublime-project}] +[{Makefile}] +indent_style = tab +indent_size = 2 + +[*.md] +# Two spaces at the end of the line means newline in Markdown +trim_trailing_whitespace = false + +[{*.py}] +indent_style = space +indent_size = 4 + +[{*.conf,*.sublime-project}] indent_style = tab indent_size = 4 diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml new file mode 100644 index 0000000000..e0ee13af07 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -0,0 +1,184 @@ +name: 🪲 Report a bug +description: Create a bug report to help improve Marlin Firmware +title: "[BUG] (bug summary)" +labels: ["Bug: Potential ?"] +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: LCD/Controller + description: Some Marlin behaviors are determined by the controller. Describe your LCD/Controller model and version. + + - type: input + attributes: + label: Other add-ons + description: Please list any other 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 0000000000..a22a1bb82e --- /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.com/servers/marlin-firmware-461605380783472640 + 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 0000000000..2e8607142c --- /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/code_of_conduct.md b/.github/code_of_conduct.md index 854fed4ec4..5fd9e0c8ee 100644 --- a/.github/code_of_conduct.md +++ b/.github/code_of_conduct.md @@ -28,15 +28,9 @@ Project maintainers are responsible for clarifying the standards of acceptable b Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful. -## Scope - -This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers. - ## Enforcement -Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at [marlinfirmware@github.com](mailto:marlinfirmware@github.com). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately. - -Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership. +Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by following GitHub's [reporting abuse or spam article](https://docs.github.com/en/communities/maintaining-your-safety-on-github/reporting-abuse-or-spam). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. ## Attribution diff --git a/.github/contributing.md b/.github/contributing.md index ef1726366a..bbf41ea1c8 100644 --- a/.github/contributing.md +++ b/.github/contributing.md @@ -26,11 +26,12 @@ The following is a set of guidelines for contributing to Marlin, hosted by the [ ## Code of Conduct -This project and everyone participating in it is governed by the [Marlin Code of Conduct](code_of_conduct.md). By participating, you are expected to uphold this code. Please report unacceptable behavior to [marlinfirmware@github.com](mailto:marlinfirmware@github.com). +This project and everyone participating in it is governed by the [Marlin Code of Conduct](code_of_conduct.md). By participating, you are expected to uphold this code. Please report unacceptable behavior by following GitHub's [reporting abuse or spam article](https://docs.github.com/en/communities/maintaining-your-safety-on-github/reporting-abuse-or-spam). ## I don't want to read this whole thing I just have a question!!! -> **Note:** Please don't file an issue to ask a question. You'll get faster results by using the resources below. +> [!NOTE] +> Please don't file an issue to ask a question. You'll get faster results by using the resources below. We have a Message Board and a Facebook group where our knowledgable user community can provide helpful advice if you have questions. @@ -42,7 +43,7 @@ We have a Message Board and a Facebook group where our knowledgable user communi If chat is more your speed, you can join the MarlinFirmware Discord server: -* Use the link https://discord.gg/n5NJ59y to join up as a General User. +* Use the link https://discord.com/servers/marlin-firmware-461605380783472640 to join up as a General User. * Even though our Discord is pretty active, it may take a while for community members to respond — please be patient! * Use the `#general` channel for general questions or discussion about Marlin. * Other channels exist for certain topics or are limited to Patrons. Check the channel list. @@ -55,7 +56,8 @@ This section guides you through submitting a Bug Report for Marlin. Following th Before creating a Bug Report, please test the "nightly" development branch, as you might find out that you don't need to create one. When you are creating a Bug Report, please [include as many details as possible](#how-do-i-submit-a-good-bug-report). Fill out [the required template](ISSUE_TEMPLATE/bug_report.yml), the information it asks for helps us resolve issues faster. -> **Note:** Regressions can happen. If you find a **Closed** issue that seems like your issue, go ahead and open a new issue and include a link to the original issue in the body of your new one. All you need to create a link is the issue number, preceded by #. For example, #8888. +> [!NOTE] +> Regressions can happen. If you find a **Closed** issue that seems like your issue, go ahead and open a new issue and include a link to the original issue in the body of your new one. All you need to create a link is the issue number, preceded by #. For example, #8888. #### How Do I Submit A (Good) Bug Report? @@ -119,7 +121,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-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. +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/workflows/auto-label.yml b/.github/workflows/auto-label.yml new file mode 100644 index 0000000000..3cbf110aa0 --- /dev/null +++ b/.github/workflows/auto-label.yml @@ -0,0 +1,41 @@ +# +# auto-label.yml +# - Find all open issues without a label and a title containing "[BUG]". +# - Apply the label "Bug: Potential ?" to these issues. +# + +name: Label Old Bugs + +on: + schedule: + - cron: "30 8 * * *" + +jobs: + autolabel: + name: Auto Label + if: github.repository == 'MarlinFirmware/Marlin' + runs-on: ubuntu-22.04 + steps: + - name: Auto Label for [BUG] + uses: actions/github-script@v7 + with: + script: | + // Get all open issues in this repository + const issueList = await github.rest.issues.listForRepo({ + owner: context.repo.owner, + repo: context.repo.repo, + state: 'open' + }); + // Filter issues without labels that have a title containing '[BUG]'. + const matchingIssues = issueList.data.filter( + issue => issue.title.includes('[BUG]') && issue.labels.length === 0 + ); + // Process the first 50 + for (const issue of matchingIssues.slice(0, 50)) { + await github.rest.issues.addLabels({ + owner: context.repo.owner, + repo: context.repo.repo, + issue_number: issue.number, + labels: ['Bug: Potential ?'] + }); + } diff --git a/.github/workflows/bump-date.yml b/.github/workflows/bump-date.yml new file mode 100644 index 0000000000..cb27ef199e --- /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-22.04 + + steps: + + - name: Check out bugfix-2.0.x + uses: actions/checkout@v4 + with: + ref: bugfix-2.0.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@v4 + 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 0000000000..a28b7fdd62 --- /dev/null +++ b/.github/workflows/check-pr.yml @@ -0,0 +1,33 @@ +# +# 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 + +jobs: + bad_target: + name: PR Bad Target + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-22.04 + + 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.1.x`. + + See [this page](https://marlinfw.org/docs/development/getting_started_pull_requests.html) for full instructions. diff --git a/.github/workflows/ci-build-tests.yml b/.github/workflows/ci-build-tests.yml new file mode 100644 index 0000000000..5d53536a27 --- /dev/null +++ b/.github/workflows/ci-build-tests.yml @@ -0,0 +1,214 @@ +# +# ci-build-tests.yml +# Do test builds to catch compile errors +# + +name: CI - Build Tests + +on: + pull_request: + branches: + - bugfix-2.1.x + - 2.1.x + paths-ignore: + - config/** + - data/** + - docs/** + - test/** + - Marlin/tests/** + - '**/*.md' + push: + branches: + - bugfix-2.1.x + - 2.1.x + - release-* + paths-ignore: + - config/** + - data/** + - docs/** + - test/** + - Marlin/tests/** + - '**/*.md' + +jobs: + test_builds: + name: Build Test + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-22.04 + + env: + CONFIG_BRANCH: ${{ github.base_ref || github.ref_name }} + + strategy: + fail-fast: true + matrix: + test-platform: + + # RP2040 + - SKR_Pico + + # Native + - linux_native + - simulator_linux_release + + # AVR + - mega2560 + - mega1280 + - at90usb1286_dfu + + # AVR Extended + - mega2560ext + - melzi_optiboot + - rambo + - sanguino1284p + - sanguino644p + + # SAM3X8E + - DUE + - DUE_archim + + # SAMD21 + - SAMD51_grandcentral_m4 + - SAMD21_minitronics20 + + # ESP32 + - esp32 + - mks_tinybee + + # Teensy 2 + #- at90usb1286_cdc + + # Teensy MK20DX256 + - teensy31 + + # Teensy MK64FX512, MK66FX1M0 + - teensy35 + + # Teensy IMXRT1062DVx6A + - teensy41 + + # STM32F0 + - malyan_M300 + - STM32F070CB_malyan + - STM32F070RB_malyan + + # STM32F1 + - chitu_f103 + - mks_robin + - mks_robin_nano_v1v2 + - PANDA_PI_V29 + - STM32F103RC_btt + - STM32F103RC_fysetc + - STM32F103RE_btt + - STM32F103RE_btt_USB + - STM32F103RE_creality + - STM32F103VE_longer + #- mks_robin_mini + #- mks_robin_nano_v1_3_f4_usbmod + #- mks_robin_nano_v1v2_usbmod + #- STM32F103CB_malyan + #- STM32F103RC_btt_USB + #- STM32F103RE + + # STM32F4 + - ARMED + - BTT_BTT002 + - BTT_GTR_V1_0 + - BTT_SKR_PRO + - FLYF407ZG + - STM32F446VE_fysetc + - LERDGEK + - LERDGEX + - mks_robin_pro2 + - Opulo_Lumen_REV3 + - rumba32 + - STM32F401RC_creality + - STM32F407VE_black + - I3DBEEZ9_V1 + + # STM32F7 + - NUCLEO_F767ZI + - REMRAM_V1 + + # STM32H7 + - BTT_SKR_SE_BX + - STM32H743VI_btt + + # STM32F1 (Maple) + - jgaurora_a5s_a1_maple + - mks_robin_lite_maple + - mks_robin_pro_maple + - STM32F103RC_btt_USB_maple + - STM32F103RC_fysetc_maple + - STM32F103RC_meeb_maple + - STM32F103VE_longer_maple + - STM32F103VE_ZM3E4V2_USB_maple + #- mks_robin_maple + #- mks_robin_nano_v1v2_maple + #- STM32F103RC_btt_maple + #- STM32F103RE_creality_maple + + # STM32G0 + - STM32G0B1RE_btt + + # HC32 + - HC32F460C_aquila_101 + + # GD32F3 + - GD32F303RE_creality_mfl + + # GD32F1 + - GD32F103RC_aquila_mfl + + # LPC176x - Lengthy tests + - LPC1768 + - LPC1769 + + steps: + + - name: Check out the PR + uses: actions/checkout@v4 + + - name: Cache pip + uses: actions/cache@v4 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-build-v1 + restore-keys: | + ${{ runner.os }}-pip-build- + + - name: Cache PlatformIO + uses: actions/cache@v4 + with: + path: | + ~/.platformio + .pio/build + .pio/libdeps + key: ${{ runner.os }}-pio-build-v1 + restore-keys: | + ${{ runner.os }}-pio-build- + + - name: Select Python 3.9 + uses: actions/setup-python@v5 + with: + python-version: '3.9' + architecture: 'x64' + + - name: Install PlatformIO + run: | + pip install -U platformio + pio upgrade --dev + pio pkg update --global + + - name: Install Simulator dependencies + run: | + sudo apt-get update + sudo apt-get install build-essential + sudo apt-get install libsdl2-dev + sudo apt-get install libsdl2-net-dev + sudo apt-get install libglm-dev + + - name: Run ${{ matrix.test-platform }} Tests + run: | + make tests-single-ci TEST_TARGET=${{ matrix.test-platform }} diff --git a/.github/workflows/ci-unit-tests.yml b/.github/workflows/ci-unit-tests.yml new file mode 100644 index 0000000000..30af812dff --- /dev/null +++ b/.github/workflows/ci-unit-tests.yml @@ -0,0 +1,78 @@ +# +# ci-unit-tests.yml +# Build and execute unit tests to catch functional issues in code +# + +name: CI - Unit Tests + +on: + pull_request: + branches: + - bugfix-2.1.x + # Cannot be enabled on 2.1.x until it contains the unit test framework + #- 2.1.x + paths-ignore: + - config/** + - data/** + - docs/** + - '**/*.md' + push: + branches: + - bugfix-2.1.x + # Cannot be enabled on 2.1.x until it contains the unit test framework + #- 2.1.x + paths-ignore: + - config/** + - data/** + - docs/** + - '**/*.md' + +jobs: + # This runs all unit tests as a single job. While it should be possible to break this up into + # multiple jobs, they currently run quickly and finish long before the compilation tests. + run_unit_tests: + name: Unit Test + # These tests will only be able to run on the bugfix-2.1.x branch, until the next release + # pulls them into additional branches. + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-22.04 + + steps: + - name: Check out the PR + uses: actions/checkout@v4 + + - name: Cache pip + uses: actions/cache@v4 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-unit-v1 + restore-keys: | + ${{ runner.os }}-pip-unit- + + - name: Cache PlatformIO + uses: actions/cache@v4 + with: + path: | + ~/.platformio + .pio/build + .pio/libdeps + key: ${{ runner.os }}-pio-tests-v1 + restore-keys: | + ${{ runner.os }}-pio-tests- + + - name: Select Python 3.9 + uses: actions/setup-python@v5 + with: + python-version: '3.9' + architecture: 'x64' + + - name: Install PlatformIO + run: | + pip install -U platformio + pio upgrade --dev + pio pkg update --global + + - name: Run All Unit Tests + run: | + make unit-test-all-local diff --git a/.github/workflows/ci-validate-boards.yml b/.github/workflows/ci-validate-boards.yml new file mode 100644 index 0000000000..aa6d284f06 --- /dev/null +++ b/.github/workflows/ci-validate-boards.yml @@ -0,0 +1,48 @@ +# +# ci-validate-boards.yml +# Validate boards.h to make sure it's all set up correctly +# + +name: CI - Validate boards.h + +# We can do the on: section as two items, one for pull requests and one for pushes... +on: + pull_request: + branches: + - bugfix-2.1.x + paths: + - "Marlin/src/core/boards.h" + push: + branches: + - bugfix-2.1.x + paths: + - "Marlin/src/core/boards.h" + +jobs: + validate_pins_files: + name: Validate boards.h + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-22.04 + + steps: + - name: Check out the PR + uses: actions/checkout@v4 + + - name: Cache pip + uses: actions/cache@v4 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-validation-v1 + restore-keys: | + ${{ runner.os }}-pip-validation- + + - name: Select Python 3.9 + uses: actions/setup-python@v5 + with: + python-version: "3.9" + architecture: "x64" + + - name: Validate core/boards.h + run: | + make validate-boards -j diff --git a/.github/workflows/ci-validate-lines.yml b/.github/workflows/ci-validate-lines.yml new file mode 100644 index 0000000000..367db12e6c --- /dev/null +++ b/.github/workflows/ci-validate-lines.yml @@ -0,0 +1,40 @@ +# +# ci-validate-lines.yml +# Validate that all text files are unchanged by linesformat.py +# + +name: CI - Validate Source Files + +on: + pull_request: + branches: + - bugfix-2.1.x + - 2.1.x + push: + branches: + - bugfix-2.1.x + - 2.1.x + +jobs: + validate_source_files: + name: Validate Source Files + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-22.04 + + steps: + - name: Check out the PR + uses: actions/checkout@v4 + + - name: Cache node_modules + uses: actions/cache@v4 + with: + path: node_modules + key: ${{ runner.os }}-npm-lines-v1 + restore-keys: | + ${{ runner.os }}-npm-lines- + + - name: Validate text file formatting + run: | + npm install --save-dev prettier + make validate-lines -j diff --git a/.github/workflows/ci-validate-pins.yml b/.github/workflows/ci-validate-pins.yml new file mode 100644 index 0000000000..2086fea37a --- /dev/null +++ b/.github/workflows/ci-validate-pins.yml @@ -0,0 +1,51 @@ +# +# ci-validate-pins.yml +# Validate that all of the pins files are unchanged by pinsformat.py +# + +name: CI - Validate Pins Files + +on: + pull_request: + branches: + - bugfix-2.1.x + # Cannot be enabled on 2.1.x until it contains the unit test framework + #- 2.1.x + paths: + - "Marlin/src/pins/*/**" + push: + branches: + - bugfix-2.1.x + # Cannot be enabled on 2.1.x until it contains the unit test framework + #- 2.1.x + paths: + - "Marlin/src/pins/*/**" + +jobs: + validate_pins_files: + name: Validate Pins Files + if: github.repository == 'MarlinFirmware/Marlin' + + runs-on: ubuntu-22.04 + + steps: + - name: Check out the PR + uses: actions/checkout@v4 + + - name: Cache pip + uses: actions/cache@v4 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-validation-v1 + restore-keys: | + ${{ runner.os }}-pip-validation- + + - name: Select Python 3.9 + uses: actions/setup-python@v5 + with: + python-version: "3.9" + architecture: "x64" + + - name: Validate all pins files + run: | + make validate-pins -j diff --git a/.github/workflows/clean-closed.yml b/.github/workflows/clean-closed.yml new file mode 100644 index 0000000000..ad0ee8ea20 --- /dev/null +++ b/.github/workflows/clean-closed.yml @@ -0,0 +1,40 @@ +# +# 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-22.04 + + strategy: + matrix: + label: + - "S: Don't Merge" + - "S: Hold for 2.1" + - "S: Please Merge" + - "S: Please Test" + - "help wanted" + - "Bug: Potential ?" + - "Needs: Discussion" + - "Needs: Documentation" + - "Needs: More Data" + - "Needs: Patch" + - "Needs: Testing" + - "Needs: Work" + + steps: + - uses: actions/checkout@v4 + - 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 0000000000..4bb488c56f --- /dev/null +++ b/.github/workflows/close-stale.yml @@ -0,0 +1,40 @@ +# +# 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-22.04 + + steps: + - uses: actions/stale@v9 + with: + repo-token: ${{ secrets.GITHUB_TOKEN }} + stale-issue-message: | + Greetings from the Marlin AutoBot! + This issue has had no activity for the last 90 days. + Do you still see this issue with the latest `bugfix-2.1.x` code? + Please add a reply within 14 days or this issue will be automatically closed. + To keep a confirmed issue open we can also add a "Bug: Confirmed" tag. + + Disclaimer: This is an open community project with lots of activity and limited + resources. The main project contributors will do a bug sweep ahead of the next + release, but any skilled member of the community may jump in at any time to fix + this issue. That can take a while depending on our busy lives so please be patient, + and take advantage of other resources such as the MarlinFirmware Discord to help + solve the issue. + days-before-stale: 90 + days-before-close: 14 + stale-issue-label: 'stale-closing-soon' + exempt-all-assignees: true + exempt-issue-labels: 'Bug: Confirmed !,T: Feature Request,Needs: More Data,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 0000000000..1435a3ef44 --- /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-22.04 + + steps: + - uses: dessant/lock-threads@v5 + with: + github-token: ${{ github.token }} + process-only: 'issues' + issue-inactive-days: '60' + exclude-issue-created-before: '' + exclude-any-issue-labels: 'no-locking' + add-issue-labels: '' + issue-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/unlock-reopened.yml b/.github/workflows/unlock-reopened.yml new file mode 100644 index 0000000000..f88e07cdc3 --- /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-22.04 + + steps: + - uses: OSDKDev/unlock-issues@v1.1 + with: + repo-token: "${{ secrets.GITHUB_TOKEN }}" diff --git a/.gitignore b/.gitignore old mode 100755 new mode 100644 index 0b852d7673..87d7ef47d3 --- a/.gitignore +++ b/.gitignore @@ -21,35 +21,26 @@ # Generated files _Version.h -bdf2u8g +bdf2u8g.exe +genpages.exe marlin_config.json mczip.h +language*.csv +out-csv/ +out-language/ *.gen *.sublime-workspace -# +# npm +node_modules/ +package.json +package-lock.json + # OS -# applet/ .DS_Store -# -# Misc -# -*~ -*.orig -*.rej -*.bak -*.idea -*.i -*.ii -*.swp -tags - -# -# C++ -# -# Compiled Object files +# Compiled C++ Object files *.slo *.lo *.o @@ -80,10 +71,7 @@ tags *.out *.app -# -# C -# -# Object files +# Compiled C Object files *.o *.ko *.obj @@ -142,14 +130,18 @@ vc-fileutils.settings # Visual Studio Code .vscode/* !.vscode/extensions.json +*.code-workspace -#Simulation +# Simulation files imgui.ini eeprom.dat spi_flash.bin +fs.img -#cmake +# CMake +buildroot/share/cmake/* CMakeLists.txt +!buildroot/share/cmake/CMakeLists.txt src/CMakeLists.txt CMakeListsPrivate.txt build/ @@ -169,3 +161,19 @@ __pycache__ # IOLogger logs *_log.csv + +# Misc. +*~ +*.orig +*.rej +*.bak +*.idea +*.i +*.ii +*.swp +tags +*.logs +*.bak +.aider* +!.aiderignore +.env diff --git a/.prettierignore b/.prettierignore new file mode 100644 index 0000000000..62761b99e9 --- /dev/null +++ b/.prettierignore @@ -0,0 +1,10 @@ +# Prettier Ignore file +*.min.js +web-ui/ +buildroot/share/PlatformIO/boards +buildroot/share/PlatformIO/variants +*.sublime-project +*.sublime-syntax +.github +.vscode +launch.json diff --git a/.vscode/extensions.json b/.vscode/extensions.json index f495d14f53..52fe2a0bdb 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -6,6 +6,7 @@ "platformio.platformio-ide" ], "unwantedRecommendations": [ + "ms-vscode-remote.remote-containers", "ms-vscode.cpptools-extension-pack" ] } diff --git a/.zed/settings.json b/.zed/settings.json new file mode 100644 index 0000000000..70bb14920c --- /dev/null +++ b/.zed/settings.json @@ -0,0 +1,16 @@ +/** + * Marlin-specific settings for Zed + * + * For a full list of overridable settings, and general information on folder-specific settings, + * see the documentation: https://zed.dev/docs/configuring-zed#settings-files + */ +{ + "languages": { + "C": { + "enable_language_server": false + }, + "C++": { + "enable_language_server": false + } + } +} diff --git a/Makefile b/Makefile index ebcdf25e2d..a63b4dc683 100644 --- a/Makefile +++ b/Makefile @@ -1,11 +1,52 @@ +SCRIPTS_DIR := buildroot/share/scripts +MAKESCRIPTS_DIR := buildroot/share/make +CONTAINER_RT_BIN := docker +CONTAINER_RT_OPTS := --rm -v $(PWD):/code -v platformio-cache:/root/.platformio +CONTAINER_IMAGE := marlin-dev +UNIT_TEST_CONFIG ?= default + +# Find a Python 3 interpreter +ifeq ($(OS),Windows_NT) + # Windows: use `where` – fall back through the three common names + PYTHON := $(shell which python 2>nul || which python3 2>nul || which py 2>nul) + # Windows: Use Python script to find pins files + PINS := $(shell $(PYTHON) $(MAKESCRIPTS_DIR)/find.py Marlin/src/pins -mindepth 2 -name 'pins_*.h') +else + # POSIX: use `command -v` – prefer python3 over python + PYTHON := $(shell command -v python3 2>/dev/null || command -v python 2>/dev/null) + # Unix/Linux: Use find command + PINS := $(shell find Marlin/src/pins -mindepth 2 -name 'pins_*.h') +endif + +# Check that the found interpreter is Python 3 +# Error if there's no Python 3 available +ifneq ($(strip $(PYTHON)),) + PYTHON_VERSION := $(shell $(PYTHON) -c "import sys; print(sys.version_info[0])" 2>/dev/null) + ifneq ($(PYTHON_VERSION),3) + $(error $(PYTHON) is not Python 3 – install a Python‑3.x interpreter or adjust your PATH) + endif +else + $(error No Python executable found – install Python 3.x and make sure it is in your PATH) +endif + help: @echo "Tasks for local development:" - @echo "* tests-single-ci: Run a single test from inside the CI" - @echo "* tests-single-local: Run a single test locally" - @echo "* tests-single-local-docker: Run a single test locally, using docker-compose" - @echo "* tests-all-local: Run all tests locally" - @echo "* tests-all-local-docker: Run all tests locally, using docker-compose" - @echo "* setup-local-docker: Setup local docker-compose" + @echo "make marlin : Build Marlin for the configured board" + @echo "make format-pins -j : Reformat all pins files (-j for parallel execution)" + @echo "make validate-lines -j : Validate line endings, fails on trailing whitespace, etc." + @echo "make validate-pins -j : Validate all pins files, fails if any require reformatting" + @echo "make validate-boards -j : Validate boards.h and pins.h for standards compliance" + @echo "make validate-urls : Validate URLs in source files" + @echo "make tests-single-ci : Run a single test from inside the CI" + @echo "make tests-single-local : Run a single test locally" + @echo "make tests-single-local-docker : Run a single test locally, using docker" + @echo "make tests-all-local : Run all tests locally" + @echo "make tests-all-local-docker : Run all tests locally, using docker" + @echo "make unit-test-single-local : Run unit tests for a single config locally" + @echo "make unit-test-single-local-docker : Run unit tests for a single config locally, using docker" + @echo "make unit-test-all-local : Run all code tests locally" + @echo "make unit-test-all-local-docker : Run all code tests locally, using docker" + @echo "make setup-local-docker : Setup local docker" @echo "" @echo "Options for testing:" @echo " TEST_TARGET Set when running tests-single-*, to select the" @@ -15,38 +56,121 @@ help: @echo " run on GitHub CI" @echo " ONLY_TEST Limit tests to only those that contain this, or" @echo " the index of the test (1-based)" + @echo " UNIT_TEST_CONFIG Set the name of the config from the test folder, without" + @echo " the leading number. Default is 'default'". Used with the + @echo " unit-test-single-* tasks" @echo " VERBOSE_PLATFORMIO If you want the full PIO output, set any value" @echo " GIT_RESET_HARD Used by CI: reset all local changes. WARNING:" @echo " THIS WILL UNDO ANY CHANGES YOU'VE MADE!" -.PHONY: help + +marlin: + ./buildroot/bin/mftest -a +.PHONY: marlin + +clean: + rm -rf .pio/build* tests-single-ci: export GIT_RESET_HARD=true - $(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) -.PHONY: tests-single-ci + $(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) PLATFORMIO_BUILD_FLAGS=-DGITHUB_ACTION tests-single-local: @if ! test -n "$(TEST_TARGET)" ; then echo "***ERROR*** Set TEST_TARGET= or use make tests-all-local" ; return 1; fi - export PATH=./buildroot/bin/:./buildroot/tests/:${PATH} \ + export PATH="./buildroot/bin/:./buildroot/tests/:${PATH}" \ && export VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) \ && run_tests . $(TEST_TARGET) "$(ONLY_TEST)" -.PHONY: tests-single-local tests-single-local-docker: @if ! test -n "$(TEST_TARGET)" ; then echo "***ERROR*** Set TEST_TARGET= or use make tests-all-local-docker" ; return 1; fi - docker-compose run --rm marlin $(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) GIT_RESET_HARD=$(GIT_RESET_HARD) ONLY_TEST="$(ONLY_TEST)" -.PHONY: tests-single-local-docker + @if ! $(CONTAINER_RT_BIN) images -q $(CONTAINER_IMAGE) > /dev/null ; then $(MAKE) setup-local-docker ; fi + $(CONTAINER_RT_BIN) run $(CONTAINER_RT_OPTS) $(CONTAINER_IMAGE) make tests-single-local TEST_TARGET=$(TEST_TARGET) VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) GIT_RESET_HARD=$(GIT_RESET_HARD) ONLY_TEST="$(ONLY_TEST)" tests-all-local: - export PATH=./buildroot/bin/:./buildroot/tests/:${PATH} \ + @$(PYTHON) -c "import yaml" 2>/dev/null || (echo 'pyyaml module is not installed. Install it with "$(PYTHON) -m pip install pyyaml"' && exit 1) + export PATH="./buildroot/bin/:./buildroot/tests/:${PATH}" \ && export VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) \ - && for TEST_TARGET in $$(./get_test_targets.py) ; do echo "Running tests for $$TEST_TARGET" ; run_tests . $$TEST_TARGET ; done -.PHONY: tests-all-local + && for TEST_TARGET in $$($(PYTHON) $(MAKESCRIPTS_DIR)/get_test_targets.py) ; do \ + if [ "$$TEST_TARGET" = "linux_native" ] && [ "$$(uname)" = "Darwin" ]; then \ + echo "Skipping tests for $$TEST_TARGET on macOS" ; \ + continue ; \ + fi ; \ + echo "Running tests for $$TEST_TARGET" ; \ + run_tests . $$TEST_TARGET || exit 1 ; \ + sleep 5; \ + done tests-all-local-docker: - docker-compose run --rm marlin $(MAKE) tests-all-local VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) GIT_RESET_HARD=$(GIT_RESET_HARD) -.PHONY: tests-all-local-docker + @if ! $(CONTAINER_RT_BIN) images -q $(CONTAINER_IMAGE) > /dev/null ; then $(MAKE) setup-local-docker ; fi + $(CONTAINER_RT_BIN) run $(CONTAINER_RT_OPTS) $(CONTAINER_IMAGE) make tests-all-local VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) GIT_RESET_HARD=$(GIT_RESET_HARD) + +unit-test-single-local: + platformio run -t marlin_$(UNIT_TEST_CONFIG) -e linux_native_test + +unit-test-single-local-docker: + @if ! $(CONTAINER_RT_BIN) images -q $(CONTAINER_IMAGE) > /dev/null ; then $(MAKE) setup-local-docker ; fi + $(CONTAINER_RT_BIN) run $(CONTAINER_RT_OPTS) $(CONTAINER_IMAGE) make unit-test-single-local UNIT_TEST_CONFIG=$(UNIT_TEST_CONFIG) + +unit-test-all-local: + platformio run -t test-marlin -e linux_native_test + +unit-test-all-local-docker: + @if ! $(CONTAINER_RT_BIN) images -q $(CONTAINER_IMAGE) > /dev/null ; then $(MAKE) setup-local-docker ; fi + $(CONTAINER_RT_BIN) run $(CONTAINER_RT_OPTS) $(CONTAINER_IMAGE) make unit-test-all-local + +USERNAME := $(shell whoami) +USER_ID := $(shell id -u) +GROUP_ID := $(shell id -g) + +.PHONY: setup-local-docker setup-local-docker-old setup-local-docker: - docker-compose build -.PHONY: setup-local-docker + @echo "Building marlin-dev Docker image..." + $(CONTAINER_RT_BIN) build -t $(CONTAINER_IMAGE) \ + --build-arg USERNAME=$(USERNAME) \ + --build-arg USER_ID=$(USER_ID) \ + --build-arg GROUP_ID=$(GROUP_ID) \ + -f docker/Dockerfile . + @echo + @echo "To run all tests in Docker:" + @echo " make tests-all-local-docker" + @echo "To run a single test in Docker:" + @echo " make tests-single-local-docker TEST_TARGET=mega2560" + +setup-local-docker-old: + $(CONTAINER_RT_BIN) buildx build -t $(CONTAINER_IMAGE) -f docker/Dockerfile . + +.PHONY: $(PINS) format-pins validate-pins + +$(PINS): %: + @echo "Formatting pins $@" + @$(PYTHON) $(SCRIPTS_DIR)/pinsformat.py $< $@ + +format-pins: $(PINS) + @echo "Processed $(words $(PINS)) pins files" + +validate-pins: format-pins + @echo "Validating pins files" + @git diff --exit-code || (git status && echo "\nError: Pins files are not formatted correctly. Run \"make format-pins\" to fix.\n" && exit 1) + +.PHONY: format-lines validate-lines validate-urls + +format-lines: + @echo "Formatting all sources" + @$(PYTHON) $(SCRIPTS_DIR)/linesformat.py buildroot + @$(PYTHON) $(SCRIPTS_DIR)/linesformat.py Marlin + +validate-lines: + @echo "Validating text formatting" + @npx prettier --check . --editorconfig --object-wrap preserve --prose-wrap never + +validate-urls: + @echo "Checking URLs in source files" + @$(MAKESCRIPTS_DIR)/check-urls.sh + +BOARDS_FILE := Marlin/src/core/boards.h + +.PHONY: validate-boards + +validate-boards: + @echo "Validating boards.h file" + @$(PYTHON) $(MAKESCRIPTS_DIR)/validate_boards.py $(BOARDS_FILE) || (echo "\nError: boards.h file is not valid. Please check and correct it.\n" && exit 1) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 2c16b8fb53..a443d4b302 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 02010100 +#define CONFIGURATION_H_VERSION 02010300 //=========================================================================== //============================= Getting Started ============================= @@ -46,12 +46,13 @@ * * Example Configs: https://github.com/MarlinFirmware/Configurations/branches/all * - * Průša Calculator: https://blog.prusaprinters.org/calculator_3416/ + * Průša Calculator: https://blog.prusa3d.com/calculator_3416/ * * Calibration Guides: https://reprap.org/wiki/Calibration * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide - * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap + * https://web.archive.org/web/20220907014303/sites.google.com/site/repraplogphase/calibration-of-your-reprap * https://youtu.be/wAL9d7FgInk + * https://teachingtechyt.github.io/calibration.html * * Calibration Objects: https://www.thingiverse.com/thing:5573 * https://www.thingiverse.com/thing:1278865 @@ -60,29 +61,9 @@ // @section info // Author info of this build printed to the host during boot and M115 -#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(MarlinFirmware)" // Original author or contributor. //#define CUSTOM_VERSION_FILE Version.h // Path from the root directory (no quotes) -/** - * *** VENDORS PLEASE READ *** - * - * Marlin allows you to add a custom boot image for Graphical LCDs. - * With this option Marlin will first show your custom screen followed - * by the standard Marlin logo with version number and web URL. - * - * We encourage you to take advantage of this new feature and we also - * respectfully request that you retain the unmodified Marlin boot screen. - */ - -// Show the Marlin bootscreen on startup. ** ENABLE FOR PRODUCTION ** -#define SHOW_BOOTSCREEN - -// Show the bitmap in Marlin/_Bootscreen.h on startup. -//#define SHOW_CUSTOM_BOOTSCREEN - -// Show the bitmap in Marlin/_Statusscreen.h on the status screen. -//#define CUSTOM_STATUS_SCREEN_IMAGE - // @section machine // Choose the name from boards.h that matches your setup @@ -90,13 +71,15 @@ #define MOTHERBOARD BOARD_RAMPS_14_EFB #endif +// @section serial + /** * Select the serial port on the board to use for communication with the host. * This allows the connection of wireless adapters (for instance) to non-default port pins. * Serial port -1 is the USB emulated serial port, if available. * Note: The first serial port (-1 or 0) will always be used by the Arduino bootloader. * - * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] + * :[-1, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9] */ #define SERIAL_PORT 0 @@ -118,29 +101,42 @@ /** * Select a secondary serial port on the board to use for communication with the host. * Currently Ethernet (-2) is only supported on Teensy 4.1 boards. - * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] + * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9] */ //#define SERIAL_PORT_2 -1 //#define BAUDRATE_2 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE /** * Select a third serial port on the board to use for communication with the host. - * Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1 - * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] + * Currently supported for AVR, DUE, SAMD51, LPC1768/9, STM32/STM32F1/HC32, and Teensy 4.x + * :[-1, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9] */ //#define SERIAL_PORT_3 1 //#define BAUDRATE_3 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE +/** + * Select a serial port to communicate with RS485 protocol + * :[-1, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + */ +//#define RS485_SERIAL_PORT 1 +#ifdef RS485_SERIAL_PORT + //#define M485_PROTOCOL 1 // Check your host for protocol compatibility + //#define RS485_BUS_BUFFER_SIZE 128 +#endif + // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH // Name displayed in the LCD "Ready" message and Info menu //#define CUSTOM_MACHINE_NAME "3D Printer" +//#define CONFIGURABLE_MACHINE_NAME // Add G-code M550 to set/report the machine name // Printer's unique ID, used by some programs to differentiate between machines. // Choose your own or use a service like https://www.uuidgenerator.net/version4 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section stepper drivers + /** * Stepper Drivers * @@ -152,9 +148,9 @@ * Options: A4988, A5984, DRV8825, LV8729, TB6560, TB6600, TMC2100, * TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE, * TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE, - * TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE, + * TMC2240, TMC2660, TMC2660_STANDALONE, * TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE - * :['A4988', 'A5984', 'DRV8825', 'LV8729', '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', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC2240', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] */ #define X_DRIVER_TYPE A4988 #define Y_DRIVER_TYPE A4988 @@ -240,21 +236,6 @@ //#define SINGLENOZZLE_STANDBY_FAN #endif -/** - * Multi-Material Unit - * Set to one of these predefined models: - * - * PRUSA_MMU1 : Průša MMU1 (The "multiplexer" version) - * PRUSA_MMU2 : Průša MMU2 - * PRUSA_MMU2S : Průša MMU2S (Requires MK3S extruder with motion sensor, EXTRUDERS = 5) - * EXTENDABLE_EMU_MMU2 : MMU with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) - * EXTENDABLE_EMU_MMU2S : MMUS with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) - * - * Requires NOZZLE_PARK_FEATURE to park print head in case MMU unit fails. - * See additional options in Configuration_adv.h. - */ -//#define MMU_MODEL PRUSA_MMU2 - // A dual extruder that uses a single stepper motor //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) @@ -265,15 +246,26 @@ #endif #endif -// A dual-nozzle that uses a servomotor to raise/lower one (or both) of the nozzles +// Switch extruders by bumping the toolhead. Requires EVENT_GCODE_TOOLCHANGE_#. +//#define MECHANICAL_SWITCHING_EXTRUDER + +/** + * A dual-nozzle that uses a servomotor to raise/lower one (or both) of the nozzles. + * Can be combined with SWITCHING_EXTRUDER. + */ //#define SWITCHING_NOZZLE #if ENABLED(SWITCHING_NOZZLE) #define SWITCHING_NOZZLE_SERVO_NR 0 //#define SWITCHING_NOZZLE_E1_SERVO_NR 1 // If two servos are used, the index of the second - #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 (single servo) or lowered/raised (dual servo) + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // A pair of angles for { E0, E1 }. + // For Dual Servo use two pairs: { { lower, raise }, { lower, raise } } #define SWITCHING_NOZZLE_SERVO_DWELL 2500 // Dwell time to wait for servo to make physical move + #define SWITCHING_NOZZLE_LIFT_TO_PROBE // Lift toolheads out of the way while probing #endif +// Switch nozzles by bumping the toolhead. Requires EVENT_GCODE_TOOLCHANGE_#. +//#define MECHANICAL_SWITCHING_NOZZLE + /** * Two separate X-carriages with extruders that connect to a moving part * via a solenoid docking mechanism. Requires SOL1_PIN and SOL2_PIN. @@ -290,7 +282,7 @@ */ //#define MAGNETIC_PARKING_EXTRUDER -#if EITHER(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER) +#if ANY(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER) #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // (mm) Distance to move beyond the parking point to grab the extruder @@ -313,6 +305,18 @@ #endif +/** + * Differential Extruder + * + * The X and E steppers work together to create a differential drive system. + * Simple : E steps = X + E ; X steps = X (E drives a loop, X stays the same) + * Balanced: E steps = X + E/2 ; X steps = X - E/2 (Dual loop system) + */ +//#define DIFFERENTIAL_EXTRUDER +#if ENABLED(DIFFERENTIAL_EXTRUDER) + //#define BALANCED_DIFFERENTIAL_EXTRUDER +#endif + /** * Switching Toolhead * @@ -388,6 +392,25 @@ //#define HOTEND_OFFSET_Y { 0.0, 5.00 } // (mm) relative Y-offset for each nozzle //#define HOTEND_OFFSET_Z { 0.0, 0.00 } // (mm) relative Z-offset for each nozzle +// @section multi-material + +/** + * Multi-Material Unit + * Set to one of these predefined models: + * + * PRUSA_MMU1 : Průša MMU1 (The "multiplexer" version) + * PRUSA_MMU2 : Průša MMU2 + * PRUSA_MMU2S : Průša MMU2S (Requires MK3S extruder with motion sensor, EXTRUDERS = 5) + * PRUSA_MMU3 : Průša MMU3 (Requires MK3S extruder with motion sensor and MMU firmware version 3.x.x, EXTRUDERS = 5) + * EXTENDABLE_EMU_MMU2 : MMU with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) + * EXTENDABLE_EMU_MMU2S : MMUS with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) + * + * Requires NOZZLE_PARK_FEATURE to park print head in case MMU unit fails. + * See additional options in Configuration_adv.h. + * :["PRUSA_MMU1", "PRUSA_MMU2", "PRUSA_MMU2S", "PRUSA_MMU3", "EXTENDABLE_EMU_MMU2", "EXTENDABLE_EMU_MMU2S"] + */ +//#define MMU_MODEL PRUSA_MMU3 + // @section psu control /** @@ -405,9 +428,18 @@ //#define PS_OFF_SOUND // Beep 1s when power off #define PSU_ACTIVE_STATE LOW // Set 'LOW' for ATX, 'HIGH' for X-Box - //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 - //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power - //#define LED_POWEROFF_TIMEOUT 10000 // (ms) Turn off LEDs after power-off, with this amount of delay + //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 + //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power + //#define LED_POWEROFF_TIMEOUT 10000 // (ms) Turn off LEDs after power-off, with this amount of delay + + //#define PSU_OFF_REDUNDANT // Second pin for redundant power control + //#define PSU_OFF_REDUNDANT_INVERTED // Redundant pin state is the inverse of PSU_ACTIVE_STATE + + //#define PS_ON1_PIN 6 // Redundant pin required to enable power in combination with PS_ON_PIN + + //#define PS_ON_EDM_PIN 8 // External Device Monitoring pins for external power control relay feedback. Fault on mismatch. + //#define PS_ON1_EDM_PIN 9 + #define PS_EDM_RESPONSE 250 // (ms) Time to allow for relay action //#define POWER_OFF_TIMER // Enable M81 D to power off after a delay //#define POWER_OFF_WAIT_FOR_COOLDOWN // Enable M81 S to power off only after cooldown @@ -417,15 +449,16 @@ //#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin #if ENABLED(AUTO_POWER_CONTROL) - #define AUTO_POWER_FANS // Turn on PSU if fans need power - #define AUTO_POWER_E_FANS - #define AUTO_POWER_CONTROLLERFAN - #define AUTO_POWER_CHAMBER_FAN - #define AUTO_POWER_COOLER_FAN + #define AUTO_POWER_FANS // Turn on PSU for fans + #define AUTO_POWER_E_FANS // Turn on PSU for E Fans + #define AUTO_POWER_CONTROLLERFAN // Turn on PSU for Controller Fan + #define AUTO_POWER_CHAMBER_FAN // Turn on PSU for Chamber Fan + #define AUTO_POWER_COOLER_FAN // Turn on PSU for Cooler Fan + #define AUTO_POWER_SPINDLE_LASER // Turn on PSU for Spindle/Laser #define POWER_TIMEOUT 30 // (s) Turn off power if the machine is idle for this duration //#define POWER_OFF_DELAY 60 // (s) Delay of poweroff after M81 command. Useful to let fans run for extra time. #endif - #if EITHER(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) //#define AUTO_POWER_E_TEMP 50 // (°C) PSU on if any extruder is over this temperature //#define AUTO_POWER_CHAMBER_TEMP 30 // (°C) PSU on if the chamber is over this temperature //#define AUTO_POWER_COOLER_TEMP 26 // (°C) PSU on if the cooler is over this temperature @@ -435,84 +468,77 @@ //=========================================================================== //============================= Thermal Settings ============================ //=========================================================================== -// @section temperature +// @section temperature sensors /** - * --NORMAL IS 4.7kΩ PULLUP!-- 1kΩ pullup can be used on hotend sensor, using correct resistor and table + * Temperature Sensors: * - * Temperature sensors available: - * - * SPI RTD/Thermocouple Boards - IMPORTANT: Read the NOTE below! - * ------- - * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-1) - * NOTE: You must uncomment/set the MAX31865_*_OHMS_n defines below. - * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-1) - * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-1) - * - * NOTE: Ensure TEMP_n_CS_PIN is set in your pins file for each TEMP_SENSOR_n using an SPI Thermocouple. By default, - * Hardware SPI on the default serial bus is used. If you have also set TEMP_n_SCK_PIN and TEMP_n_MISO_PIN, - * Software SPI will be used on those ports instead. You can force Hardware SPI on the default bus in the - * Configuration_adv.h file. At this time, separate Hardware SPI buses for sensors are not supported. - * - * Analog Themocouple Boards - * ------- - * -4 : AD8495 with Thermocouple - * -1 : AD595 with Thermocouple + * NORMAL IS 4.7kΩ PULLUP! Hotend sensors can use 1kΩ pullup with correct resistor and table. * + * ================================================================ * Analog Thermistors - 4.7kΩ pullup - Normal - * ------- - * 1 : 100kΩ EPCOS - Best choice for EPCOS thermistors - * 331 : 100kΩ Same as #1, but 3.3V scaled for MEGA - * 332 : 100kΩ Same as #1, but 3.3V scaled for DUE - * 2 : 200kΩ ATC Semitec 204GT-2 - * 202 : 200kΩ Copymaster 3D - * 3 : ???Ω Mendel-parts thermistor - * 4 : 10kΩ Generic Thermistor !! DO NOT use for a hotend - it gives bad resolution at high temp. !! - * 5 : 100kΩ ATC Semitec 104GT-2/104NT-4-R025H42G - Used in ParCan, J-Head, and E3D, SliceEngineering 300°C - * 501 : 100kΩ Zonestar - Tronxy X3A - * 502 : 100kΩ Zonestar - used by hot bed in Zonestar Průša P802M - * 503 : 100kΩ Zonestar (Z8XM2) Heated Bed thermistor - * 504 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-B3950) Hotend Thermistor - * 505 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-3950) Bed Thermistor - * 512 : 100kΩ RPW-Ultra hotend - * 6 : 100kΩ EPCOS - Not as accurate as table #1 (created using a fluke thermocouple) - * 7 : 100kΩ Honeywell 135-104LAG-J01 - * 71 : 100kΩ Honeywell 135-104LAF-J01 - * 8 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT - * 9 : 100kΩ GE Sensing AL03006-58.2K-97-G1 - * 10 : 100kΩ RS PRO 198-961 - * 11 : 100kΩ Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1% - * 12 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed - * 13 : 100kΩ Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% - * 15 : 100kΩ Calibrated for JGAurora A5 hotend - * 18 : 200kΩ ATC Semitec 204GT-2 Dagoma.Fr - MKS_Base_DKU001327 - * 22 : 100kΩ GTM32 Pro vB - hotend - 4.7kΩ pullup to 3.3V and 220Ω to analog input - * 23 : 100kΩ GTM32 Pro vB - bed - 4.7kΩ pullup to 3.3v and 220Ω to analog input - * 30 : 100kΩ Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K - beta 3950 - * 60 : 100kΩ Maker's Tool Works Kapton Bed Thermistor - beta 3950 - * 61 : 100kΩ Formbot/Vivedino 350°C Thermistor - beta 3950 - * 66 : 4.7MΩ Dyze Design High Temperature Thermistor - * 67 : 500kΩ SliceEngineering 450°C Thermistor - * 68 : PT100 amplifier board from Dyze Design - * 70 : 100kΩ bq Hephestos 2 - * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 - * 2000 : 100kΩ Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor + * ================================================================ + * 1 : 100kΩ EPCOS - Best choice for EPCOS thermistors + * 331 : 100kΩ Same as #1, but 3.3V scaled for MEGA + * 332 : 100kΩ Same as #1, but 3.3V scaled for DUE + * 2 : 200kΩ ATC Semitec 204GT-2 + * 202 : 200kΩ Copymaster 3D + * 3 : ???Ω Mendel-parts thermistor + * 4 : 10kΩ Generic Thermistor !! DO NOT use for a hotend - it gives bad resolution at high temp. !! + * 5 : 100kΩ ATC Semitec 104GT-2/104NT-4-R025H42G - Used in ParCan, J-Head, and E3D, SliceEngineering 300°C + * 501 : 100kΩ Zonestar - Tronxy X3A + * 502 : 100kΩ Zonestar - used by hot bed in Zonestar Průša P802M + * 503 : 100kΩ Zonestar (Z8XM2) Heated Bed thermistor + * 504 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-B3950) Hotend Thermistor + * 505 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-3950) Bed Thermistor + * 512 : 100kΩ RPW-Ultra hotend + * 6 : 100kΩ EPCOS - Not as accurate as table #1 (created using a fluke thermocouple) + * 7 : 100kΩ Honeywell 135-104LAG-J01 + * 71 : 100kΩ Honeywell 135-104LAF-J01 + * 8 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT + * 9 : 100kΩ GE Sensing AL03006-58.2K-97-G1 + * 10 : 100kΩ RS PRO 198-961 + * 11 : 100kΩ Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1% + * 12 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed + * 13 : 100kΩ Hisense up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% + * 14 : 100kΩ (R25), 4092K (beta25), 4.7kΩ pull-up, bed thermistor as used in Ender-5 S1 + * 15 : 100kΩ Calibrated for JGAurora A5 hotend + * 17 : 100kΩ Dagoma NTC white thermistor + * 18 : 200kΩ ATC Semitec 204GT-2 Dagoma.Fr - MKS_Base_DKU001327 + * 22 : 100kΩ GTM32 Pro vB - hotend - 4.7kΩ pullup to 3.3V and 220Ω to analog input + * 23 : 100kΩ GTM32 Pro vB - bed - 4.7kΩ pullup to 3.3v and 220Ω to analog input + * 30 : 100kΩ Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K - beta 3950 + * 60 : 100kΩ Maker's Tool Works Kapton Bed Thermistor - beta 3950 + * 61 : 100kΩ Formbot/Vivedino 350°C Thermistor - beta 3950 + * 66 : 4.7MΩ Dyze Design / Trianglelab T-D500 500°C High Temperature Thermistor + * 67 : 500kΩ SliceEngineering 450°C Thermistor + * 68 : PT100 Smplifier board from Dyze Design + * 70 : 100kΩ bq Hephestos 2 + * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 + * 666 : 200kΩ Einstart S custom thermistor with 10k pullup. + * 2000 : 100kΩ Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor * - * Analog Thermistors - 1kΩ pullup - Atypical, and requires changing out the 4.7kΩ pullup for 1kΩ. - * ------- (but gives greater accuracy and more stable PID) - * 51 : 100kΩ EPCOS (1kΩ pullup) - * 52 : 200kΩ ATC Semitec 204GT-2 (1kΩ pullup) - * 55 : 100kΩ ATC Semitec 104GT-2 - Used in ParCan & J-Head (1kΩ pullup) + * ================================================================ + * Analog Thermistors - 1kΩ pullup + * Atypical, and requires changing out the 4.7kΩ pullup for 1kΩ. + * (but gives greater accuracy and more stable PID) + * ================================================================ + * 51 : 100kΩ EPCOS (1kΩ pullup) + * 52 : 200kΩ ATC Semitec 204GT-2 (1kΩ pullup) + * 55 : 100kΩ ATC Semitec 104GT-2 - Used in ParCan & J-Head (1kΩ pullup) * + * ================================================================ * Analog Thermistors - 10kΩ pullup - Atypical - * ------- - * 99 : 100kΩ Found on some Wanhao i3 machines with a 10kΩ pull-up resistor + * ================================================================ + * 99 : 100kΩ Found on some Wanhao i3 machines with a 10kΩ pull-up resistor * + * ================================================================ * Analog RTDs (Pt100/Pt1000) - * ------- + * ================================================================ * 110 : Pt100 with 1kΩ pullup (atypical) * 147 : Pt100 with 4.7kΩ pullup * 1010 : Pt1000 with 1kΩ pullup (atypical) + * 1022 : Pt1000 with 2.2kΩ pullup * 1047 : Pt1000 with 4.7kΩ pullup (E3D) * 20 : Pt100 with circuit in the Ultimainboard V2.x with mainboard ADC reference voltage = INA826 amplifier-board supply voltage. * NOTE: (1) Must use an ADC input with no pullup. (2) Some INA826 amplifiers are unreliable at 3.3V so consider using sensor 147, 110, or 21. @@ -520,15 +546,39 @@ * NOTE: ADC pins are not 5V tolerant. Not recommended because it's possible to damage the CPU by going over 500°C. * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x * + * ================================================================ + * SPI RTD/Thermocouple Boards + * ================================================================ + * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-2 and bed) + * NOTE: You must uncomment/set the MAX31865_*_OHMS_n defines below. + * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-2 and bed) + * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-2 and bed) + * + * NOTE: Ensure TEMP_n_CS_PIN is set in your pins file for each TEMP_SENSOR_n using an SPI Thermocouple. By default, + * Hardware SPI on the default serial bus is used. If you have also set TEMP_n_SCK_PIN and TEMP_n_MISO_PIN, + * Software SPI will be used on those ports instead. You can force Hardware SPI on the default bus in the + * Configuration_adv.h file. At this time, separate Hardware SPI buses for sensors are not supported. + * + * ================================================================ + * Analog Thermocouple Boards + * ================================================================ + * -4 : AD8495 with Thermocouple + * -1 : AD595 with Thermocouple + * + * ================================================================ + * SoC internal sensor + * ================================================================ + * 100 : SoC internal sensor + * + * ================================================================ * Custom/Dummy/Other Thermal Sensors - * ------ + * ================================================================ * 0 : not used * 1000 : Custom - Specify parameters in Configuration_adv.h * * !!! Use these for Testing or Development purposes. NEVER for production machine. !!! * 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below. * 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below. - * */ #define TEMP_SENSOR_0 1 #define TEMP_SENSOR_1 0 @@ -538,18 +588,19 @@ #define TEMP_SENSOR_5 0 #define TEMP_SENSOR_6 0 #define TEMP_SENSOR_7 0 -#define TEMP_SENSOR_BED 0 +#define TEMP_SENSOR_BED 1 #define TEMP_SENSOR_PROBE 0 #define TEMP_SENSOR_CHAMBER 0 #define TEMP_SENSOR_COOLER 0 #define TEMP_SENSOR_BOARD 0 +#define TEMP_SENSOR_SOC 0 #define TEMP_SENSOR_REDUNDANT 0 // Dummy thermistor constant temperature readings, for use with 998 and 999 #define DUMMY_THERMISTOR_998_VALUE 25 #define DUMMY_THERMISTOR_999_VALUE 100 -// Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1 +// Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1 / 2 / BED #if TEMP_SENSOR_IS_MAX_TC(0) #define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) #define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 @@ -558,6 +609,14 @@ #define MAX31865_SENSOR_OHMS_1 100 #define MAX31865_CALIBRATION_OHMS_1 430 #endif +#if TEMP_SENSOR_IS_MAX_TC(2) + #define MAX31865_SENSOR_OHMS_2 100 + #define MAX31865_CALIBRATION_OHMS_2 430 +#endif +#if TEMP_SENSOR_IS_MAX_TC(BED) + #define MAX31865_SENSOR_OHMS_BED 100 + #define MAX31865_CALIBRATION_OHMS_BED 430 +#endif #if HAS_E_TEMP_SENSOR #define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 @@ -593,6 +652,8 @@ #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort. #endif +// @section temperature + // Below this temperature the heater will be switched off // because it probably indicates a broken thermistor wire. #define HEATER_0_MINTEMP 5 @@ -636,47 +697,64 @@ // @section hotend temp -// Enable PIDTEMP for PID control or MPCTEMP for Predictive Model. -// temperature control. Disable both for bang-bang heating. -#define PIDTEMP // See the PID Tuning Guide at https://reprap.org/wiki/PID_Tuning -//#define MPCTEMP // ** EXPERIMENTAL ** +/** + * Temperature Control + * + * (NONE) : Bang-bang heating + * PIDTEMP : PID temperature control (~4.1K) + * MPCTEMP : Predictive Model temperature control. (~1.8K without auto-tune) + */ +#define PIDTEMP // See the PID Tuning Guide at https://reprap.org/wiki/PID_Tuning +//#define MPCTEMP // See https://marlinfw.org/docs/features/model_predictive_control.html -#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current -#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current -#define PID_K1 0.95 // Smoothing factor within any PID loop +#define PID_MAX 255 // Limit hotend current while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current +#define PID_K1 0.95 // Smoothing factor within any PID loop #if ENABLED(PIDTEMP) - //#define PID_DEBUG // Print PID debug data to the serial port. Use 'M303 D' to toggle activation. + //#define MIN_POWER 0 // Min power to improve PID stability (0..PID_MAX). + // Get the power from the temperature report ('M105' => @:nnn) and try P*2-20 to P*2-10. + //#define PID_DEBUG // Print PID debug data to the serial port. Use 'M303 D' to enable/disable. //#define PID_PARAMS_PER_HOTEND // Use separate PID parameters for each extruder (useful for mismatched extruders) // 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. // If there are fewer values, the last one applies to the remaining hotends. - #define DEFAULT_Kp_LIST { 22.20, 22.20 } - #define DEFAULT_Ki_LIST { 1.08, 1.08 } - #define DEFAULT_Kd_LIST { 114.00, 114.00 } + #define DEFAULT_KP_LIST { 22.20, 22.20 } + #define DEFAULT_KI_LIST { 1.08, 1.08 } + #define DEFAULT_KD_LIST { 114.00, 114.00 } #else - #define DEFAULT_Kp 22.20 - #define DEFAULT_Ki 1.08 - #define DEFAULT_Kd 114.00 + #define DEFAULT_KP 22.20 + #define DEFAULT_KI 1.08 + #define DEFAULT_KD 114.00 #endif +#else + #define BANG_MAX 255 // Limit hotend current while in bang-bang mode; 255=full current #endif /** * Model Predictive Control for hotend * - * Use a physical model of the hotend to control temperature. When configured correctly - * this gives better responsiveness and stability than PID and it also removes the need - * for PID_EXTRUSION_SCALING and PID_FAN_SCALING. Use M306 T to autotune the model. - * @section mpctemp + * Use a physical model of the hotend to control temperature. When configured correctly this gives + * better responsiveness and stability than PID and removes the need for PID_EXTRUSION_SCALING + * and PID_FAN_SCALING. Enable MPC_AUTOTUNE and use M306 T to autotune the model. + * @section mpc temp */ #if ENABLED(MPCTEMP) - //#define MPC_EDIT_MENU // Add MPC editing to the "Advanced Settings" menu. (~1300 bytes of flash) + #define MPC_AUTOTUNE // Include a method to do MPC auto-tuning (~6.3K bytes of flash) + #if ENABLED(MPC_AUTOTUNE) + //#define MPC_AUTOTUNE_DEBUG // Enable MPC debug logging (~870 bytes of flash) + #endif + //#define MPC_EDIT_MENU // Add MPC editing to the "Advanced Settings" menu. (~1.3K bytes of flash) //#define MPC_AUTOTUNE_MENU // Add MPC auto-tuning to the "Advanced Settings" menu. (~350 bytes of flash) - #define MPC_MAX BANG_MAX // (0..255) Current to nozzle while MPC is active. - #define MPC_HEATER_POWER { 40.0f } // (W) Heat cartridge powers. + #define MPC_MAX 255 // (0..255) Current to nozzle while MPC is active. + #define MPC_HEATER_POWER { 40.0f } // (W) Nominal heat cartridge powers. + //#define MPC_PTC // Hotend power changes with temperature (e.g., PTC heat cartridges). + #if ENABLED(MPC_PTC) + #define MPC_HEATER_ALPHA { 0.0028f } // Temperature coefficient of resistance of the heat cartridges. + #define MPC_HEATER_REFTEMP { 20 } // (°C) Reference temperature for MPC_HEATER_POWER and MPC_HEATER_ALPHA. + #endif #define MPC_INCLUDE_FAN // Model the fan speed? @@ -694,8 +772,12 @@ //#define MPC_FAN_0_ACTIVE_HOTEND #endif + // Filament Heat Capacity (joules/kelvin/mm) + // Set at runtime with M306 H #define FILAMENT_HEAT_CAPACITY_PERMM { 5.6e-3f } // 0.0056 J/K/mm for 1.75mm PLA (0.0149 J/K/mm for 2.85mm PLA). - //#define FILAMENT_HEAT_CAPACITY_PERMM { 3.6e-3f } // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG). + // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG). + // 0.00515 J/K/mm for 1.75mm ABS (0.0137 J/K/mm for 2.85mm ABS). + // 0.00522 J/K/mm for 1.75mm Nylon (0.0138 J/K/mm for 2.85mm Nylon). // Advanced options #define MPC_SMOOTHING_FACTOR 0.5f // (0.0...1.0) Noisy temperature sensors may need a lower value for stabilization. @@ -704,29 +786,14 @@ #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. + //#define EVENT_GCODE_AFTER_MPC_TUNE "M84" // G-code to execute after MPC tune finished and Z raised. #endif //=========================================================================== //====================== PID > Bed Temperature Control ====================== //=========================================================================== -/** - * PID Bed Heating - * - * If this option is enabled set PID constants below. - * If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis. - * - * The PID frequency will be the same as the extruder PWM. - * If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz, - * which is fine for driving a square wave into a resistive load and does not significantly - * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W - * heater. If your configuration is significantly different than this and you don't understand - * the issues involved, don't use bed PID until someone else verifies that your hardware works. - * @section bed temp - */ -//#define PIDTEMPBED - -//#define BED_LIMIT_SWITCHING +// @section bed temp /** * Max Bed Power @@ -736,18 +803,72 @@ */ #define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current +/** + * PID Bed Heating + * + * The PID frequency will be the same as the extruder PWM. + * If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz, + * which is fine for driving a square wave into a resistive load and does not significantly + * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W + * heater. If your configuration is significantly different than this and you don't understand + * the issues involved, don't use bed PID until someone else verifies that your hardware works. + * + * With this option disabled, bang-bang will be used. BED_LIMIT_SWITCHING enables hysteresis. + */ +//#define PIDTEMPBED + #if ENABLED(PIDTEMPBED) - //#define MIN_BED_POWER 0 - //#define PID_BED_DEBUG // Print Bed PID debug data to the serial port. + //#define MIN_BED_POWER 0 // Min power to improve PID stability (0..MAX_BED_POWER). + // Get the power from the temperature report ('M105' => B@:nnn) and try P*2-20 to P*2-10. + //#define PID_BED_DEBUG // Print Bed PID debug data to the serial port. Use 'M303 D' to enable/disable. // 120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) // from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) - #define DEFAULT_bedKp 10.00 - #define DEFAULT_bedKi .023 - #define DEFAULT_bedKd 305.4 + #define DEFAULT_BED_KP 10.00 + #define DEFAULT_BED_KI 0.023 + #define DEFAULT_BED_KD 305.4 // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. -#endif // PIDTEMPBED +#else + //#define BED_LIMIT_SWITCHING // Keep the bed temperature within BED_HYSTERESIS of the target +#endif + +/** + * Peltier Bed - Heating and Cooling + * + * A Peltier device transfers heat from one side to the other in proportion to the amount of + * current flowing through the device and the direction of current flow. So the same device + * can both heat and cool. + * + * When "cooling" in addition to rejecting the heat transferred from the hot side to the cold + * side, the dissipated power (voltage * current) must also be rejected. Be sure to set up a + * fan that can be powered in sync with the Peltier unit. + * + * This feature is only set up to run in bang-bang mode because Peltiers don't handle PWM + * well without filter circuitry. + * + * Since existing 3D printers are made to handle relatively high current for the heated bed, + * we can use the heated bed power pins to control the Peltier power using the same G-codes + * as the heated bed (M140, M190, etc.). + * + * A second GPIO pin is required to control current direction. + * Two configurations are possible: Relay and H-Bridge + * + * (At this time only relay is supported. H-bridge requires 4 MOS switches configured in H-Bridge.) + * + * Power is handled by the bang-bang control loop: 0 or 255. + * Cooling applications are more common than heating, so the pin states are commonly: + * LOW = Heating = Relay Energized + * HIGH = Cooling = Relay in "Normal" state + */ +//#define PELTIER_BED +#if ENABLED(PELTIER_BED) + #define PELTIER_DIR_PIN -1 // Relay control pin for Peltier + #define PELTIER_DIR_HEAT_STATE LOW // The relay pin state that causes the Peltier to heat +#endif + +// Add 'M190 R T' for more gradual M190 R bed cooling. +//#define BED_ANNEALING_GCODE //=========================================================================== //==================== PID > Chamber Temperature Control ==================== @@ -780,24 +901,26 @@ #define MAX_CHAMBER_POWER 255 // limits duty cycle to chamber heater; 255=full current #if ENABLED(PIDTEMPCHAMBER) - #define MIN_CHAMBER_POWER 0 - //#define PID_CHAMBER_DEBUG // Print Chamber PID debug data to the serial port. + //#define MIN_CHAMBER_POWER 0 // Min power to improve PID stability. (0..MAX_CHAMBER_POWER) + // Get the power from the temperature report ('M105' => C@:nnn) and try P*2-20 to P*2-10. + //#define PID_CHAMBER_DEBUG // Print Chamber PID debug data to the serial port. Use 'M303 D' to enable/disable. // Lasko "MyHeat Personal Heater" (200w) modified with a Fotek SSR-10DA to control only the heating element // and placed inside the small Creality printer enclosure tent. - // - #define DEFAULT_chamberKp 37.04 - #define DEFAULT_chamberKi 1.40 - #define DEFAULT_chamberKd 655.17 + #define DEFAULT_CHAMBER_KP 37.04 + #define DEFAULT_CHAMBER_KI 1.40 + #define DEFAULT_CHAMBER_KD 655.17 // M309 P37.04 I1.04 D655.17 // FIND YOUR OWN: "M303 E-2 C8 S50" to run autotune on the chamber at 50 degreesC for 8 cycles. #endif // PIDTEMPCHAMBER +// @section pid temp + #if ANY(PIDTEMP, PIDTEMPBED, PIDTEMPCHAMBER) //#define PID_OPENLOOP // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay - #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature + #define PID_FUNCTIONAL_RANGE 20 // If the temperature difference between the target temperature and the actual temperature // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. //#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of flash) @@ -833,7 +956,7 @@ * protect against a broken or disconnected thermistor wire. * * The issue: If a thermistor falls out, it will report the much lower - * temperature of the air in the room, and the the firmware will keep + * temperature of the air in the room, and the firmware will keep * the heater on. * * If you get "Thermal Runaway" or "Heating failed" errors the @@ -849,7 +972,7 @@ //============================= Mechanical Settings ========================= //=========================================================================== -// @section machine +// @section kinematics // Enable one of the options below for CoreXY, CoreXZ, or CoreYZ kinematics, // either in the usual order or reversed @@ -859,17 +982,35 @@ //#define COREYX //#define COREZX //#define COREZY -//#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042 + +// +// MarkForged Kinematics +// See https://reprap.org/forum/read.php?152,504042 +// +//#define MARKFORGED_XY //#define MARKFORGED_YX +#if ANY(MARKFORGED_XY, MARKFORGED_YX) + //#define MARKFORGED_INVERSE // Enable for an inverted Markforged kinematics belt path +#endif // Enable for a belt style printer with endless "Z" motion //#define BELTPRINTER +// 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 + +// @section polargraph + // Enable for Polargraph Kinematics //#define POLARGRAPH #if ENABLED(POLARGRAPH) - #define POLARGRAPH_MAX_BELT_LEN 1035.0 - #define POLAR_SEGMENTS_PER_SECOND 5 + #define POLARGRAPH_MAX_BELT_LEN 1035.0 // (mm) Belt length at full extension. Override with M665 H. + #define DEFAULT_SEGMENTS_PER_SECOND 5 // Move segmentation based on duration + #define PEN_UP_DOWN_MENU // Add "Pen Up" and "Pen Down" to the MarlinUI menu #endif // @section delta @@ -881,36 +1022,31 @@ // 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 + #define DEFAULT_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. + // Add three-point calibration to the MarlinUI menu. // 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) + // 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) + // 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 + #if ANY(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU) + // Step size for paper-test 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) + #define PRINTABLE_RADIUS 140.0 // (mm) // Center-to-center distance of the holes in the diagonal push rods. #define DELTA_DIAGONAL_ROD 250.0 // (mm) @@ -918,7 +1054,7 @@ // Distance between bed and nozzle Z home position #define DELTA_HEIGHT 250.00 // (mm) Get this value from G33 auto calibrate - #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // (mm) Get these values from G33 auto calibrate // Horizontal distance bridged by diagonal push rods when effector is centered. #define DELTA_RADIUS 124.0 // (mm) Get this value from G33 auto calibrate @@ -926,12 +1062,13 @@ // Trim adjustments for individual towers // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 // measured in degrees anticlockwise looking from above the printer - #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // (mm) Get these values from G33 auto calibrate - // Delta radius and diagonal rod adjustments (mm) - //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } -#endif + // Delta radius and diagonal rod adjustments + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } // (mm) + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } // (mm) + +#endif // DELTA // @section scara @@ -945,9 +1082,9 @@ */ //#define MORGAN_SCARA //#define MP_SCARA -#if EITHER(MORGAN_SCARA, MP_SCARA) +#if ANY(MORGAN_SCARA, MP_SCARA) // If movement is choppy try lowering this value - #define SCARA_SEGMENTS_PER_SECOND 200 + #define DEFAULT_SEGMENTS_PER_SECOND 200 // Length of inner and outer support arms. Measure arm lengths precisely. #define SCARA_LINKAGE_1 150 // (mm) @@ -961,14 +1098,11 @@ #if ENABLED(MORGAN_SCARA) //#define DEBUG_SCARA_KINEMATICS - #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly + #define 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 @@ -983,66 +1117,104 @@ // Enable for TPARA kinematics and configure below //#define AXEL_TPARA #if ENABLED(AXEL_TPARA) - #define DEBUG_ROBOT_KINEMATICS - #define ROBOT_SEGMENTS_PER_SECOND 200 + #define DEBUG_TPARA_KINEMATICS + #define DEFAULT_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) + #define TPARA_LINKAGE_1 120 // (mm) + #define TPARA_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) + // Height of the Shoulder axis (pivot) relative to the tower floor + #define TPARA_SHOULDER_AXIS_HEIGHT 135.0 // (mm) - #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly + // The position of the last linkage relative to the robot arm origin + // (intersection of the base axis and floor) when at the home position + #define TPARA_ARM_X_HOME_POS 28.75 // (mm) Measured from shoulder axis to tool holder axis in home position + #define TPARA_ARM_Y_HOME_POS 0 // (mm) + #define TPARA_ARM_Z_HOME_POS 250.00 // (mm) Measured from tool holder axis to the floor + + // TPARA Workspace offset relative to the tower (position of workspace origin relative to robot Tower origin ) + // This needs to be reasonably accurate as it defines the printbed position in the TPARA space. + #define TPARA_OFFSET_X 127.0 // (mm) to coincide with minimum radius MIDDLE_DEAD_ZONE_R, and W(0,0,0) is reachable + #define TPARA_OFFSET_Y 0.0 // (mm) + #define TPARA_OFFSET_Z 0.0 // (mm) + + // TPARA tool connection point offset, relative to the tool moving frame origin which is in the last linkage axis, + // (TCP: tool center/connection point) of the robot, + // the plane of measured offset must be alligned with home position plane + #define TPARA_TCP_OFFSET_X 27.0 // (mm) Tool flange: 27 (distance from pivot to bolt holes), extruder tool: 50.0, + #define TPARA_TCP_OFFSET_Y 0.0 // (mm) + #define TPARA_TCP_OFFSET_Z -65.0 // (mm) Tool flange (bottom): -6 (caution as Z 0 posiion will crash second linkage to the floor, -35 is safe for testing with no tool), extruder tool (depends on extruder): -65.0 + + #define 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) + // For now use a hardcoded uniform limit, although it should be calculated, or fix a limit for each axis angle + #define MIDDLE_DEAD_ZONE_R 100 // (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 + // Max angle between L1 and L2 + #define TPARA_MAX_L1L2_ANGLE 140.0f // (degrees) +#endif // AXEL_TPARA + +// @section polar + +/** + * POLAR Kinematics + * developed by Kadir ilkimen for PolarBear CNC and babyBear + * https://github.com/kadirilkimen/Polar-Bear-Cnc-Machine + * https://github.com/kadirilkimen/babyBear-3D-printer + * + * A polar machine can have different configurations. + * This kinematics is only compatible with the following configuration: + * X : Independent linear + * Y or B : Polar + * Z : Independent linear + * + * For example, PolarBear has CoreXZ plus Polar Y or B. + * + * Motion problem for Polar axis near center / origin: + * + * 3D printing: + * Movements very close to the center of the polar axis take more time than others. + * This brief delay results in more material deposition due to the pressure in the nozzle. + * + * Current Kinematics and feedrate scaling deals with this by making the movement as fast + * as possible. It works for slow movements but doesn't work well with fast ones. A more + * complicated extrusion compensation must be implemented. + * + * Ideally, it should estimate that a long rotation near the center is ahead and will cause + * unwanted deposition. Therefore it can compensate the extrusion beforehand. + * + * Laser cutting: + * Same thing would be a problem for laser engraving too. As it spends time rotating at the + * center point, more likely it will burn more material than it should. Therefore similar + * compensation would be implemented for laser-cutting operations. + * + * Milling: + * This shouldn't be a problem for cutting/milling operations. + */ +//#define POLAR +#if ENABLED(POLAR) + #define DEFAULT_SEGMENTS_PER_SECOND 180 // If movement is choppy try lowering this value + #define PRINTABLE_RADIUS 82.0f // (mm) Maximum travel of X axis + + // Movements fall inside POLAR_FAST_RADIUS are assigned the highest possible feedrate + // to compensate unwanted deposition related to the near-origin motion problem. + #define POLAR_FAST_RADIUS 3.0f // (mm) + + // Radius which is unreachable by the tool. + // Needed if the tool is not perfectly aligned to the center of the polar axis. + #define POLAR_CENTER_OFFSET 0.0f // (mm) + + #define FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly #endif -// @section machine - -// 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 =========================== //=========================================================================== // @section endstops -// Specify here all the endstop connectors that are connected to any endstop or probe. -// Almost all printers will be using one per axis. Probes will use one or more of the -// extra connectors. Leave undefined any used for non-endstop and non-probe purposes. -#define USE_XMIN_PLUG -#define USE_YMIN_PLUG -#define USE_ZMIN_PLUG -//#define USE_IMIN_PLUG -//#define USE_JMIN_PLUG -//#define USE_KMIN_PLUG -//#define USE_UMIN_PLUG -//#define USE_VMIN_PLUG -//#define USE_WMIN_PLUG -//#define USE_XMAX_PLUG -//#define USE_YMAX_PLUG -//#define USE_ZMAX_PLUG -//#define USE_IMAX_PLUG -//#define USE_JMAX_PLUG -//#define USE_KMAX_PLUG -//#define USE_UMAX_PLUG -//#define USE_VMAX_PLUG -//#define USE_WMAX_PLUG - // Enable pullup for all endstops to prevent a floating state #define ENDSTOPPULLUPS #if DISABLED(ENDSTOPPULLUPS) @@ -1093,26 +1265,29 @@ //#define ENDSTOPPULLDOWN_ZMIN_PROBE #endif -// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). -#define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define U_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define V_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define W_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define U_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define V_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#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. +/** + * Endstop "Hit" State + * Set to the state (HIGH or LOW) that applies to each endstop. + */ +#define X_MIN_ENDSTOP_HIT_STATE HIGH +#define X_MAX_ENDSTOP_HIT_STATE HIGH +#define Y_MIN_ENDSTOP_HIT_STATE HIGH +#define Y_MAX_ENDSTOP_HIT_STATE HIGH +#define Z_MIN_ENDSTOP_HIT_STATE HIGH +#define Z_MAX_ENDSTOP_HIT_STATE HIGH +#define I_MIN_ENDSTOP_HIT_STATE HIGH +#define I_MAX_ENDSTOP_HIT_STATE HIGH +#define J_MIN_ENDSTOP_HIT_STATE HIGH +#define J_MAX_ENDSTOP_HIT_STATE HIGH +#define K_MIN_ENDSTOP_HIT_STATE HIGH +#define K_MAX_ENDSTOP_HIT_STATE HIGH +#define U_MIN_ENDSTOP_HIT_STATE HIGH +#define U_MAX_ENDSTOP_HIT_STATE HIGH +#define V_MIN_ENDSTOP_HIT_STATE HIGH +#define V_MAX_ENDSTOP_HIT_STATE HIGH +#define W_MIN_ENDSTOP_HIT_STATE HIGH +#define W_MAX_ENDSTOP_HIT_STATE HIGH +#define Z_MIN_PROBE_ENDSTOP_HIT_STATE HIGH // 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. @@ -1157,11 +1332,16 @@ /** * Default Axis Steps Per Unit (linear=steps/mm, rotational=steps/°) - * Override with M92 + * Override with M92 (when enabled below) * X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 500 } +/** + * Enable support for M92. Disable to save at least ~530 bytes of flash. + */ +#define EDITABLE_STEPS_PER_UNIT + /** * Default Max Feed Rate (linear=mm/s, rotational=°/s) * Override with M203 @@ -1212,6 +1392,7 @@ #define DEFAULT_XJERK 10.0 #define DEFAULT_YJERK 10.0 #define DEFAULT_ZJERK 0.3 + #define DEFAULT_EJERK 5.0 //#define DEFAULT_IJERK 0.3 //#define DEFAULT_JJERK 0.3 //#define DEFAULT_KJERK 0.3 @@ -1227,8 +1408,6 @@ #endif #endif -#define DEFAULT_EJERK 5.0 // May be used by Linear Advance - /** * Junction Deviation Factor * @@ -1251,6 +1430,11 @@ * See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained */ //#define S_CURVE_ACCELERATION +#if ENABLED(S_CURVE_ACCELERATION) + // Define to use 4th instead of 6th order motion curve + //#define S_CURVE_FACTOR 0.25 // Initial and final acceleration factor, ideally 0.1 to 0.4. + // Shouldn't generally require tuning. +#endif //=========================================================================== //============================= Z Probe Options ============================= @@ -1274,19 +1458,17 @@ /** * Z_MIN_PROBE_PIN * - * Define this pin if the probe is not connected to Z_MIN_PIN. - * If not defined the default pin for the selected MOTHERBOARD - * will be used. Most of the time the default is what you want. + * Override this pin only if the probe cannot be connected to + * the default Z_MIN_PROBE_PIN for the selected MOTHERBOARD. * * - The simplest option is to use a free endstop connector. * - Use 5V for powered (usually inductive) sensors. * - * - RAMPS 1.3/1.4 boards may use the 5V, GND, and Aux4->D32 pin: - * - For simple switches connect... - * - normally-closed switches to GND and D32. - * - normally-open switches to 5V and D32. + * - For simple switches... + * - Normally-closed (NC) also connect to GND. + * - Normally-open (NO) also connect to 5V. */ -//#define Z_MIN_PROBE_PIN 32 // Pin 32 is the RAMPS default +//#define Z_MIN_PROBE_PIN -1 /** * Probe Type @@ -1317,8 +1499,13 @@ /** * Z Servo Probe, such as an endstop switch on a rotating arm. */ -//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector. -//#define Z_SERVO_ANGLES { 70, 0 } // Z Servo Deploy and Stow angles +//#define Z_PROBE_SERVO_NR 0 +#ifdef Z_PROBE_SERVO_NR + //#define Z_SERVO_ANGLES { 70, 0 } // Z Servo Deploy and Stow angles + //#define Z_SERVO_MEASURE_ANGLE 45 // Use if the servo must move to a "free" position for measuring after deploy + //#define Z_SERVO_INTERMEDIATE_STOW // Stow the probe between points + //#define Z_SERVO_DEACTIVATE_AFTER_STOW // Deactivate the servo when probe is stowed +#endif /** * The BLTouch probe uses a Hall effect sensor and emulates a servo. @@ -1344,7 +1531,7 @@ * on the right, enable and set TOUCH_MI_DEPLOY_XPOS to the deploy position. * * Also requires: BABYSTEPPING, BABYSTEP_ZPROBE_OFFSET, Z_SAFE_HOMING, - * and a minimum Z_HOMING_HEIGHT of 10. + * and a minimum Z_CLEARANCE_FOR_HOMING of 10. */ //#define TOUCH_MI_PROBE #if ENABLED(TOUCH_MI_PROBE) @@ -1353,6 +1540,29 @@ //#define TOUCH_MI_MANUAL_DEPLOY // For manual deploy (LCD menu) #endif +/** + * Bed Distance Sensor + * + * Measures the distance from bed to nozzle with accuracy of 0.01mm. + * For information about this sensor https://github.com/markniu/Bed_Distance_sensor + * Uses I2C port, so it requires I2C library markyue/Panda_SoftMasterI2C. + */ +//#define BD_SENSOR +#if ENABLED(BD_SENSOR) + //#define BD_SENSOR_PROBE_NO_STOP // Probe bed without stopping at each probe point +#endif + +/** + * BIQU MicroProbe + * + * A lightweight, solenoid-driven probe. + * For information about this sensor https://github.com/bigtreetech/MicroProbe + * + * Also requires PROBE_ENABLE_DISABLE + */ +//#define BIQU_MICROPROBE_V1 // Triggers HIGH +//#define BIQU_MICROPROBE_V2 // Triggers LOW + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE @@ -1376,6 +1586,20 @@ #define PROBE_DEPLOY_FEEDRATE (133*60) // (mm/min) Probe deploy speed #define PROBE_STOW_FEEDRATE (133*60) // (mm/min) Probe stow speed + /** + * Magnetically Mounted Probe with a Servo mechanism + * Probe Deploy and Stow both follow the same basic sequence: + * - Rotate the SERVO to its Deployed angle + * - Perform XYZ moves to deploy or stow the PROBE + * - Rotate the SERVO to its Stowed angle + */ + //#define MAG_MOUNTED_PROBE_SERVO_NR 0 // Servo Number for this probe + #ifdef MAG_MOUNTED_PROBE_SERVO_NR + #define MAG_MOUNTED_PROBE_SERVO_ANGLES { 90, 0 } // Servo Angles for Deployed, Stowed + #define MAG_MOUNTED_PRE_DEPLOY { PROBE_DEPLOY_FEEDRATE, { 15, 160, 30 } } // Safe position for servo activation + #define MAG_MOUNTED_PRE_STOW { PROBE_DEPLOY_FEEDRATE, { 15, 160, 30 } } // Safe position for servo deactivation + #endif + #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 @@ -1388,7 +1612,7 @@ #define MAG_MOUNTED_STOW_5 { PROBE_STOW_FEEDRATE, { 0, 0, 0 } } // Extra move if needed #endif -// Duet Smart Effector (for delta printers) - https://bit.ly/2ul5U7J +// Duet Smart Effector (for delta printers) - https://docs.duet3d.com/en/Duet3D_hardware/Accessories/Smart_Effector // When the pin is defined you can use M672 to set/reset the probe sensitivity. //#define DUET_SMART_EFFECTOR #if ENABLED(DUET_SMART_EFFECTOR) @@ -1404,7 +1628,7 @@ //#define SENSORLESS_PROBING /** - * Allen key retractable z-probe as seen on many Kossel delta printers - https://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe + * Allen key retractable z-probe as seen on many Kossel delta printers - https://reprap.org/wiki/Kossel#Autolevel_probe * Deploys by touching z-axis belt. Retracts by pushing the probe down. */ //#define Z_PROBE_ALLEN_KEY @@ -1412,13 +1636,13 @@ // 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 { 30.0, 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 { 0.0, 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 { 0.0, (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 @@ -1439,7 +1663,7 @@ * Nozzle-to-Probe offsets { X, Y, Z } * * X and Y offset - * Use a caliper or ruler to measure the distance from the tip of + * Use a caliper or ruler to measure the distance (in mm) from the tip of * the Nozzle to the center-point of the Probe in the X and Y axes. * * Z offset @@ -1451,7 +1675,7 @@ * * Tune and Adjust * - Probe Offsets can be tuned at runtime with 'M851', LCD menus, babystepping, etc. - * - PROBE_OFFSET_WIZARD (configuration_adv.h) can be used for setting the Z offset. + * - PROBE_OFFSET_WIZARD (Configuration_adv.h) can be used for setting the Z offset. * * Assuming the typical work area orientation: * - Probe to RIGHT of the Nozzle has a Positive X offset @@ -1475,20 +1699,29 @@ * | [-] | * O-- FRONT --+ */ -#define NOZZLE_TO_PROBE_OFFSET { 10, 10, 0 } +#define NOZZLE_TO_PROBE_OFFSET { 10, 10, 0 } // (mm) X, Y, Z distance from Nozzle tip to Probe trigger-point + +// Enable and set to use a specific tool for probing. Disable to allow any tool. +#define PROBING_TOOL 0 +#ifdef PROBING_TOOL + //#define PROBE_TOOLCHANGE_NO_MOVE // Suppress motion on probe tool-change +#endif + +//#define PROBE_WAKEUP_TIME_MS 30 // (ms) Time for the probe to wake up // Most probes should stay away from the edges of the bed, but // with NOZZLE_AS_PROBE this can be negative for a wider probing area. #define PROBING_MARGIN 10 -// X and Y axis travel speed (mm/min) between probes -#define XY_PROBE_FEEDRATE (133*60) +// X and Y axis travel speed between probes. +// Leave undefined to use the average of the current XY homing feedrate. +#define XY_PROBE_FEEDRATE (133*60) // (mm/min) -// Feedrate (mm/min) for the first approach when double-probing (MULTIPLE_PROBING == 2) -#define Z_PROBE_FEEDRATE_FAST (4*60) +// Feedrate for the first approach when double-probing (MULTIPLE_PROBING == 2) +#define Z_PROBE_FEEDRATE_FAST (4*60) // (mm/min) -// Feedrate (mm/min) for the "accurate" probe of each point -#define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2) +// Feedrate for the "accurate" probe of each point +#define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2) // (mm/min) /** * Probe Activation Switch @@ -1512,6 +1745,7 @@ #define PROBE_TARE_DELAY 200 // (ms) Delay after tare before #define PROBE_TARE_STATE HIGH // State to write pin for tare //#define PROBE_TARE_PIN PA5 // Override default pin + //#define PROBE_TARE_MENU // Display a menu item to tare the probe #if ENABLED(PROBE_ACTIVATION_SWITCH) //#define PROBE_TARE_ONLY_WHILE_INACTIVE // Fail to tare/probe if PROBE_ACTIVATION_SWITCH is active #endif @@ -1549,19 +1783,24 @@ * probe Z Offset set with NOZZLE_TO_PROBE_OFFSET, M851, or the LCD. * Only integer values >= 1 are valid here. * - * Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle. - * But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle. + * Example: 'M851 Z-5' with a CLEARANCE of 4 => 9mm from bed to nozzle. + * But: 'M851 Z+1' with a CLEARANCE of 2 => 2mm from bed to nozzle. */ -#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow -#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points -#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes -//#define Z_AFTER_PROBING 5 // Z position after probing is done +#define Z_CLEARANCE_DEPLOY_PROBE 10 // (mm) Z Clearance for Deploy/Stow +#define Z_CLEARANCE_BETWEEN_PROBES 5 // (mm) Z Clearance between probe points +#define Z_CLEARANCE_MULTI_PROBE 5 // (mm) Z Clearance between multiple probes +#define Z_PROBE_ERROR_TOLERANCE 3 // (mm) Tolerance for early trigger (<= -probe.offset.z + ZPET) +//#define Z_AFTER_PROBING 5 // (mm) Z position after probing is done -#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping +#define Z_PROBE_LOW_POINT -2 // (mm) Farthest distance below the trigger-point to go before stopping -// For M851 give a range for adjusting the Z probe offset -#define Z_PROBE_OFFSET_RANGE_MIN -20 -#define Z_PROBE_OFFSET_RANGE_MAX 20 +// For M851 provide ranges for adjusting the X, Y, and Z probe offsets +//#define PROBE_OFFSET_XMIN -50 // (mm) +//#define PROBE_OFFSET_XMAX 50 // (mm) +//#define PROBE_OFFSET_YMIN -50 // (mm) +//#define PROBE_OFFSET_YMAX 50 // (mm) +//#define PROBE_OFFSET_ZMIN -20 // (mm) +//#define PROBE_OFFSET_ZMAX 20 // (mm) // Enable the M48 repeatability test to test probe accuracy //#define Z_MIN_PROBE_REPEATABILITY_TEST @@ -1596,40 +1835,39 @@ #define PROBING_BED_TEMP 50 #endif +// @section stepper drivers + // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 -// :{ 0:'Low', 1:'High' } -#define X_ENABLE_ON 0 -#define Y_ENABLE_ON 0 -#define Z_ENABLE_ON 0 -#define E_ENABLE_ON 0 // For all extruders -//#define I_ENABLE_ON 0 -//#define J_ENABLE_ON 0 -//#define K_ENABLE_ON 0 -//#define U_ENABLE_ON 0 -//#define V_ENABLE_ON 0 -//#define W_ENABLE_ON 0 +// :['LOW', 'HIGH'] +#define X_ENABLE_ON LOW +#define Y_ENABLE_ON LOW +#define Z_ENABLE_ON LOW +#define E_ENABLE_ON LOW // For all extruders +//#define I_ENABLE_ON LOW +//#define J_ENABLE_ON LOW +//#define K_ENABLE_ON LOW +//#define U_ENABLE_ON LOW +//#define V_ENABLE_ON LOW +//#define W_ENABLE_ON LOW // Disable axis steppers immediately when they're not being stepped. // WARNING: When motors turn off there is a chance of losing position accuracy! -#define DISABLE_X false -#define DISABLE_Y false -#define DISABLE_Z false -//#define DISABLE_I false -//#define DISABLE_J false -//#define DISABLE_K false -//#define DISABLE_U false -//#define DISABLE_V false -//#define DISABLE_W false - -// Turn off the display blinking that warns about possible accuracy reduction -//#define DISABLE_REDUCED_ACCURACY_WARNING +//#define DISABLE_X +//#define DISABLE_Y +//#define DISABLE_Z +//#define DISABLE_I +//#define DISABLE_J +//#define DISABLE_K +//#define DISABLE_U +//#define DISABLE_V +//#define DISABLE_W // @section extruder -#define DISABLE_E false // Disable the extruder when not stepping -#define DISABLE_INACTIVE_EXTRUDER // Keep only the active extruder enabled +//#define DISABLE_E // Disable the extruder when not stepping +#define DISABLE_OTHER_EXTRUDERS // Keep only the active extruder enabled -// @section machine +// @section stepper drivers // Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way. #define INVERT_X_DIR false @@ -1642,8 +1880,6 @@ //#define INVERT_V_DIR false //#define INVERT_W_DIR false -// @section extruder - // For direct drive extruder v9 set to true, for geared extruder set to false. #define INVERT_E0_DIR false #define INVERT_E1_DIR false @@ -1666,10 +1902,13 @@ */ //#define Z_IDLE_HEIGHT Z_HOME_POS -//#define Z_HOMING_HEIGHT 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ... - // Be sure to have this much clearance over your Z_MAX_POS to prevent grinding. +//#define Z_CLEARANCE_FOR_HOMING 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ... + // You'll need this much clearance above Z_MAX_POS to avoid grinding. -//#define Z_AFTER_HOMING 10 // (mm) Height to move to after homing Z +//#define Z_AFTER_HOMING 10 // (mm) Height to move to after homing (if Z was homed) +//#define XY_AFTER_HOMING { 10, 10 } // (mm) Move to an XY position after homing (and raising Z) + +//#define EVENT_GCODE_AFTER_HOMING "M300 P440 S200" // Commands to run after G28 (and move to XY_AFTER_HOMING) // Direction of endstops when homing; 1=MAX, -1=MIN // :[-1,1] @@ -1683,6 +1922,21 @@ //#define V_HOME_DIR -1 //#define W_HOME_DIR -1 +/** + * Safety Stops + * If an axis has endstops on both ends the one specified above is used for + * homing, while the other can be used for things like SD_ABORT_ON_ENDSTOP_HIT. + */ +//#define X_SAFETY_STOP +//#define Y_SAFETY_STOP +//#define Z_SAFETY_STOP +//#define I_SAFETY_STOP +//#define J_SAFETY_STOP +//#define K_SAFETY_STOP +//#define U_SAFETY_STOP +//#define V_SAFETY_STOP +//#define W_SAFETY_STOP + // @section geometry // The size of the printable area @@ -1746,11 +2000,13 @@ #define MAX_SOFTWARE_ENDSTOP_W #endif -#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) +#if ANY(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) //#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD #endif /** + * @section filament runout sensors + * * Filament Runout Sensors * Mechanical or opto endstops are used to check for the presence of filament. * @@ -1822,8 +2078,52 @@ // as the filament moves. (Be sure to set FILAMENT_RUNOUT_DISTANCE_MM // large enough to avoid false positives.) //#define FILAMENT_MOTION_SENSOR - #endif -#endif + + #if ENABLED(FILAMENT_MOTION_SENSOR) + //#define FILAMENT_SWITCH_AND_MOTION // Define separate pins below to sense motion + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + + #define FILAMENT_MOTION_DISTANCE_MM 3.0 // (mm) Missing distance required to trigger runout + + #define NUM_MOTION_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_MOTION#_PIN for each. + //#define FIL_MOTION1_PIN -1 + + // Override individually if the motion sensors vary + //#define FIL_MOTION1_STATE LOW + //#define FIL_MOTION1_PULLUP + //#define FIL_MOTION1_PULLDOWN + + //#define FIL_MOTION2_STATE LOW + //#define FIL_MOTION2_PULLUP + //#define FIL_MOTION2_PULLDOWN + + //#define FIL_MOTION3_STATE LOW + //#define FIL_MOTION3_PULLUP + //#define FIL_MOTION3_PULLDOWN + + //#define FIL_MOTION4_STATE LOW + //#define FIL_MOTION4_PULLUP + //#define FIL_MOTION4_PULLDOWN + + //#define FIL_MOTION5_STATE LOW + //#define FIL_MOTION5_PULLUP + //#define FIL_MOTION5_PULLDOWN + + //#define FIL_MOTION6_STATE LOW + //#define FIL_MOTION6_PULLUP + //#define FIL_MOTION6_PULLDOWN + + //#define FIL_MOTION7_STATE LOW + //#define FIL_MOTION7_PULLUP + //#define FIL_MOTION7_PULLDOWN + + //#define FIL_MOTION8_STATE LOW + //#define FIL_MOTION8_PULLUP + //#define FIL_MOTION8_PULLDOWN + #endif // FILAMENT_SWITCH_AND_MOTION + #endif // FILAMENT_MOTION_SENSOR + #endif // FILAMENT_RUNOUT_DISTANCE_MM +#endif // FILAMENT_RUNOUT_SENSOR //=========================================================================== //=============================== Bed Leveling ============================== @@ -1869,6 +2169,18 @@ //#define AUTO_BED_LEVELING_UBL //#define MESH_BED_LEVELING +/** + * Commands to execute at the start of G29 probing, + * after switching to the PROBING_TOOL. + */ +//#define EVENT_GCODE_BEFORE_G29 "M300 P440 S200" + +/** + * Commands to execute at the end of G29 probing. + * Useful to retract or move the Z probe out of the way. + */ +//#define EVENT_GCODE_AFTER_G29 "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" + /** * Normally G28 leaves leveling disabled on completion. Enable one of * these options to restore the prior leveling state or to always enable @@ -1886,19 +2198,10 @@ #define LEVELING_BED_TEMP 50 #endif -/** - * Bed Distance Sensor - * - * Measures the distance from bed to nozzle with accuracy of 0.01mm. - * For information about this sensor https://github.com/markniu/Bed_Distance_sensor - * Uses I2C port, so it requires I2C library markyue/Panda_SoftMasterI2C. - */ -//#define BD_SENSOR - /** * Enable detailed logging of G28, G29, M48, etc. * Turn on with the command 'M111 S32'. - * NOTE: Requires a lot of PROGMEM! + * NOTE: Requires a lot of flash! */ //#define DEBUG_LEVELING_FEATURE @@ -1908,17 +2211,21 @@ #endif #if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL) - // Gradually reduce leveling correction until a set height is reached, - // at which point movement will be level to the machine's XY plane. - // The height can be set with M420 Z + /** + * Gradually reduce leveling correction until a set height is reached, + * at which point movement will be level to the machine's XY plane. + * The height can be set with M420 Z + */ #define ENABLE_LEVELING_FADE_HEIGHT #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) #define DEFAULT_LEVELING_FADE_HEIGHT 10.0 // (mm) Default fade height. #endif - // For Cartesian machines, instead of dividing moves on mesh boundaries, - // split up moves into short segments like a Delta. This follows the - // contours of the bed more closely than edge-to-edge straight moves. + /** + * For Cartesian machines, instead of dividing moves on mesh boundaries, + * split up moves into short segments like a Delta. This follows the + * contours of the bed more closely than edge-to-edge straight moves. + */ #define SEGMENT_LEVELED_MOVES #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one) @@ -1938,7 +2245,7 @@ #endif -#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) +#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) // Set the number of grid points per dimension. #define GRID_MAX_POINTS_X 3 @@ -1954,7 +2261,7 @@ //#define EXTRAPOLATE_BEYOND_GRID // - // Experimental Subdivision of the grid by Catmull-Rom method. + // Subdivision of the grid by Catmull-Rom method. // Synthesizes intermediate points to produce a more detailed mesh. // //#define ABL_BILINEAR_SUBDIVISION @@ -1979,6 +2286,9 @@ //#define UBL_HILBERT_CURVE // Use Hilbert distribution for less travel when probing multiple points + //#define UBL_TILT_ON_MESH_POINTS // Use nearest mesh points with G29 J for better Z reference + //#define UBL_TILT_ON_MESH_POINTS_3POINT // Use nearest mesh points with G29 J0 (3-point) + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500 @@ -1987,6 +2297,25 @@ //#define UBL_MESH_WIZARD // Run several commands in a row to get a complete mesh + /** + * Probing not allowed within the position of an obstacle. + */ + //#define AVOID_OBSTACLES + #if ENABLED(AVOID_OBSTACLES) + #define CLIP_W 23 // Bed clip width, should be padded a few mm over its physical size + #define CLIP_H 14 // Bed clip height, should be padded a few mm over its physical size + + // Obstacle Rectangles defined as { X1, Y1, X2, Y2 } + #define OBSTACLE1 { (X_BED_SIZE) / 4 - (CLIP_W) / 2, 0, (X_BED_SIZE) / 4 + (CLIP_W) / 2, CLIP_H } + #define OBSTACLE2 { (X_BED_SIZE) * 3 / 4 - (CLIP_W) / 2, 0, (X_BED_SIZE) * 3 / 4 + (CLIP_W) / 2, CLIP_H } + #define OBSTACLE3 { (X_BED_SIZE) / 4 - (CLIP_W) / 2, (Y_BED_SIZE) - (CLIP_H), (X_BED_SIZE) / 4 + (CLIP_W) / 2, Y_BED_SIZE } + #define OBSTACLE4 { (X_BED_SIZE) * 3 / 4 - (CLIP_W) / 2, (Y_BED_SIZE) - (CLIP_H), (X_BED_SIZE) * 3 / 4 + (CLIP_W) / 2, Y_BED_SIZE } + + // The probed grid must be inset for G29 J. This is okay, since it is + // only used to compute a linear transformation for the mesh itself. + #define G29J_MESH_TILT_MARGIN ((CLIP_H) + 1) + #endif + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== @@ -1994,7 +2323,7 @@ //=========================================================================== #define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed - #define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited. + #define GRID_MAX_POINTS_X 3 #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X //#define MESH_G28_REST_ORIGIN // After homing all axes ('G28' or 'G28 XYZ') rest Z at Z_MIN_POS @@ -2018,8 +2347,8 @@ #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_HEIGHT 0.0 // (mm) Z height of nozzle at tramming points + #define BED_TRAMMING_Z_HOP 4.0 // (mm) Z raise between tramming points //#define BED_TRAMMING_INCLUDE_CENTER // Move to the center after the last corner //#define BED_TRAMMING_USE_PROBE #if ENABLED(BED_TRAMMING_USE_PROBE) @@ -2048,12 +2377,6 @@ #define BED_TRAMMING_LEVELING_ORDER { LF, RF, RB, LB } #endif -/** - * Commands to execute at the end of G29 probing. - * Useful to retract or move the Z probe out of the way. - */ -//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" - // @section homing // The center of the bed is at (X=0, Y=0) @@ -2081,13 +2404,17 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT X_CENTER // X point for Z homing - #define Z_SAFE_HOMING_Y_POINT Y_CENTER // Y point for Z homing + #define Z_SAFE_HOMING_X_POINT X_CENTER // (mm) X point for Z homing + #define Z_SAFE_HOMING_Y_POINT Y_CENTER // (mm) Y point for Z homing + //#define Z_SAFE_HOMING_POINT_ABSOLUTE // Ignore home offsets (M206) for Z homing position #endif // Homing speeds (linear=mm/min, rotational=°/min) #define HOMING_FEEDRATE_MM_M { (50*60), (50*60), (4*60) } +// Edit homing feedrates with M210 and MarlinUI menu items +//#define EDITABLE_HOMING_FEEDRATE + // Validate that endstops are triggered on homing moves #define VALIDATE_HOMING_ENDSTOPS @@ -2129,9 +2456,8 @@ #define XY_DIAG_BD 282.8427124746 #define XY_SIDE_AD 200 - // Or, set the default skew factors directly here - // to override the above measurements: - #define XY_SKEW_FACTOR 0.0 + // Or, set the XY skew factor directly: + //#define XY_SKEW_FACTOR 0.0 //#define SKEW_CORRECTION_FOR_Z #if ENABLED(SKEW_CORRECTION_FOR_Z) @@ -2140,8 +2466,10 @@ #define YZ_DIAG_AC 282.8427124746 #define YZ_DIAG_BD 282.8427124746 #define YZ_SIDE_AD 200 - #define XZ_SKEW_FACTOR 0.0 - #define YZ_SKEW_FACTOR 0.0 + + // Or, set the Z skew factors directly: + //#define XZ_SKEW_FACTOR 0.0 + //#define YZ_SKEW_FACTOR 0.0 #endif // Enable this option for M852 to set skew at runtime @@ -2165,7 +2493,7 @@ */ //#define EEPROM_SETTINGS // Persistent storage with M500 and M501 //#define DISABLE_M503 // Saves ~2700 bytes of flash. Disable for release! -#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM. +#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save flash. #define EEPROM_BOOT_SILENT // Keep M503 quiet and only give errors during first load #if ENABLED(EEPROM_SETTINGS) //#define EEPROM_AUTO_INIT // Init EEPROM automatically on any errors. @@ -2196,10 +2524,10 @@ // //#define TEMPERATURE_UNITS_SUPPORT -// @section temperature +// @section temperature presets // -// Preheat Constants - Up to 6 are supported without changes +// Preheat Constants - Up to 10 are supported without changes // #define PREHEAT_1_LABEL "PLA" #define PREHEAT_1_TEMP_HOTEND 180 @@ -2213,9 +2541,9 @@ #define PREHEAT_2_TEMP_CHAMBER 35 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// @section motion - /** + * @section nozzle park + * * Nozzle Park * * Park the nozzle at the given XYZ position on idle or G27. @@ -2238,7 +2566,9 @@ #endif /** - * Clean Nozzle Feature -- EXPERIMENTAL + * @section nozzle clean + * + * Clean Nozzle Feature * * Adds the G12 command to perform a nozzle cleaning process. * @@ -2272,28 +2602,33 @@ * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. * * Caveats: The ending Z should be the same as starting Z. - * Attention: EXPERIMENTAL. G-code arguments may change. */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) - // Default number of pattern repetitions - #define NOZZLE_CLEAN_STROKES 12 + #define NOZZLE_CLEAN_PATTERN_LINE // Provide 'G12 P0' - a simple linear cleaning pattern + #define NOZZLE_CLEAN_PATTERN_ZIGZAG // Provide 'G12 P1' - a zigzag cleaning pattern + #define NOZZLE_CLEAN_PATTERN_CIRCLE // Provide 'G12 P2' - a circular cleaning pattern - // Default number of triangles - #define NOZZLE_CLEAN_TRIANGLES 3 + // Default pattern to use when 'P' is not provided to G12. One of the enabled options above. + #define NOZZLE_CLEAN_DEFAULT_PATTERN 0 + + #define NOZZLE_CLEAN_STROKES 12 // Default number of pattern repetitions + + #if ENABLED(NOZZLE_CLEAN_PATTERN_ZIGZAG) + #define NOZZLE_CLEAN_TRIANGLES 3 // Default number of triangles + #endif // Specify positions for each tool as { { X, Y, Z }, { X, Y, Z } } // Dual hotend system may use { { -20, (Y_BED_SIZE / 2), (Z_MIN_POS + 1) }, { 420, (Y_BED_SIZE / 2), (Z_MIN_POS + 1) }} #define NOZZLE_CLEAN_START_POINT { { 30, 30, (Z_MIN_POS + 1) } } #define NOZZLE_CLEAN_END_POINT { { 100, 60, (Z_MIN_POS + 1) } } - // Circular pattern radius - #define NOZZLE_CLEAN_CIRCLE_RADIUS 6.5 - // Circular pattern circle fragments number - #define NOZZLE_CLEAN_CIRCLE_FN 10 - // Middle point of circle - #define NOZZLE_CLEAN_CIRCLE_MIDDLE NOZZLE_CLEAN_START_POINT + #if ENABLED(NOZZLE_CLEAN_PATTERN_CIRCLE) + #define NOZZLE_CLEAN_CIRCLE_RADIUS 6.5 // (mm) Circular pattern radius + #define NOZZLE_CLEAN_CIRCLE_FN 10 // Circular pattern circle number of segments + #define NOZZLE_CLEAN_CIRCLE_MIDDLE NOZZLE_CLEAN_START_POINT // Middle point of circle + #endif // Move the nozzle to the initial position after cleaning #define NOZZLE_CLEAN_GOBACK @@ -2357,7 +2692,7 @@ */ //#define PRINTCOUNTER #if ENABLED(PRINTCOUNTER) - #define PRINTCOUNTER_SAVE_INTERVAL 60 // (minutes) EEPROM save interval during print + #define PRINTCOUNTER_SAVE_INTERVAL 60 // (minutes) EEPROM save interval during print. A value of 0 will save stats at end of print. #endif // @section security @@ -2387,15 +2722,30 @@ #define PASSWORD_ON_STARTUP #define PASSWORD_UNLOCK_GCODE // Unlock with the M511 P command. Disable to prevent brute-force attack. #define PASSWORD_CHANGE_GCODE // Change the password with M512 P S. - //#define PASSWORD_ON_SD_PRINT_MENU // This does not prevent gcodes from running + //#define PASSWORD_ON_SD_PRINT_MENU // This does not prevent G-codes from running //#define PASSWORD_AFTER_SD_PRINT_END //#define PASSWORD_AFTER_SD_PRINT_ABORT //#include "Configuration_Secure.h" // External file with PASSWORD_DEFAULT_VALUE #endif -//============================================================================= -//============================= LCD and SD support ============================ -//============================================================================= +// @section media + +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + */ +//#define SDSUPPORT + +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ +#if ENABLED(SDSUPPORT) + //#define SD_CHECK_AND_RETRY +#endif // @section interface @@ -2436,27 +2786,12 @@ #define DISPLAY_CHARSET_HD44780 JAPANESE /** - * Info Screen Style (0:Classic, 1:Průša) + * Info Screen Style (0:Classic, 1:Průša, 2:CNC) * - * :[0:'Classic', 1:'Průša'] + * :[0:'Classic', 1:'Průša', 2:'CNC'] */ #define LCD_INFO_SCREEN_STYLE 0 -/** - * SD CARD - * - * SD Card support is disabled by default. If your controller has an SD slot, - * you must uncomment the following option or it won't work. - */ -//#define SDSUPPORT - -/** - * SD CARD: ENABLE CRC - * - * Use CRC checks and retries on the SD communication. - */ -//#define SD_CHECK_AND_RETRY - /** * LCD Menu Items * @@ -2549,6 +2884,18 @@ //#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2 //#define LCD_FEEDBACK_FREQUENCY_HZ 5000 +// +// Tone queue size, used to keep beeps from blocking execution. +// Default is 4, or override here. Costs 4 bytes of SRAM per entry. +// +//#define TONE_QUEUE_LENGTH 4 + +// +// A sequence of tones to play at startup, in pairs of tone (Hz), duration (ms). +// Silence in-between tones. +// +//#define STARTUP_TUNE { 698, 300, 0, 50, 523, 50, 0, 25, 494, 50, 0, 25, 523, 100, 0, 50, 554, 300, 0, 100, 523, 300 } + //============================================================================= //======================== LCD / Controller Selection ========================= //======================== (Character-based LCDs) ========================= @@ -2573,7 +2920,7 @@ // // Original RADDS LCD Display+Encoder+SDCardReader -// http://doku.radds.org/dokumentation/lcd-display/ +// https://web.archive.org/web/20200719145306/doku.radds.org/dokumentation/lcd-display/ // //#define RADDS_DISPLAY @@ -2603,7 +2950,6 @@ // // RigidBot Panel V1.0 -// http://www.inventapart.com/ // //#define RIGIDBOT_PANEL @@ -2613,13 +2959,15 @@ // //#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602 -// -// ANET and Tronxy 20x4 Controller -// -//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin. - // This LCD is known to be susceptible to electrical interference - // which scrambles the display. Pressing any button clears it up. - // This is a LCD2004 display with 5 analog buttons. +/** + * ANET and Tronxy 20x4 Controller + * LCD2004 display with 5 analog buttons. + * + * NOTE: Requires ADC_KEYPAD_PIN to be assigned to an analog pin. + * This LCD is known to be susceptible to electrical interference which + * scrambles the display. Press any button to clear it up. + */ +//#define ZONESTAR_LCD // // Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD. @@ -2640,15 +2988,16 @@ // // Elefu RA Board Control Panel -// http://www.elefu.com/index.php?route=product/product&product_id=53 +// https://web.archive.org/web/20140823033947/www.elefu.com/index.php?route=product/product&product_id=53 // //#define RA_CONTROL_PANEL // // Sainsmart (YwRobot) LCD Displays // -// These require F.Malpartida's LiquidCrystal_I2C library -// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home +// These require LiquidCrystal_I2C library: +// https://github.com/MarlinFirmware/New-LiquidCrystal +// https://github.com/fmalpartida/New-LiquidCrystal/wiki // //#define LCD_SAINSMART_I2C_1602 //#define LCD_SAINSMART_I2C_2004 @@ -2681,7 +3030,7 @@ // // -// 2-wire Non-latching LCD SR from https://goo.gl/aJJ4sH +// 2-wire Non-latching LCD SR from https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection // LCD configuration: https://reprap.org/wiki/SAV_3D_LCD // //#define SAV_3DLCD @@ -2728,7 +3077,7 @@ // // ReprapWorld Graphical LCD -// https://reprapworld.com/?products_details&products_id/1218 +// https://reprapworld.com/electronics/3d-printer-modules/autonomous-printing/graphical-lcd-screen-v1-0/ // //#define REPRAPWORLD_GRAPHICAL_LCD @@ -2753,7 +3102,7 @@ // // MaKr3d Makr-Panel with graphic controller and SD support. -// https://reprap.org/wiki/MaKr3d_MaKrPanel +// https://reprap.org/wiki/MaKrPanel // //#define MAKRPANEL @@ -2771,7 +3120,7 @@ // // Cartesio UI -// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// https://web.archive.org/web/20180605050442/mauk.cc/webshop/cartesio-shop/electronics/user-interface // //#define CARTESIO_UI @@ -2806,7 +3155,7 @@ // // FYSETC variant of the MINI12864 graphic controller with SD support -// https://wiki.fysetc.com/Mini12864_Panel/ +// https://wiki.fysetc.com/docs/Mini12864Panel // //#define FYSETC_MINI_12864_X_X // Type C/D/E/F. No tunable RGB Backlight by default //#define FYSETC_MINI_12864_1_2 // Type C/D/E/F. Simple RGB Backlight (always on) @@ -2815,16 +3164,21 @@ //#define FYSETC_GENERIC_12864_1_1 // Larger display with basic ON/OFF backlight. // -// BigTreeTech Mini 12864 V1.0 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. +// BigTreeTech Mini 12864 V1.0 / V2.0 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. +// https://github.com/bigtreetech/MINI-12864 // -//#define BTT_MINI_12864_V1 +//#define BTT_MINI_12864 // -// Factory display for Creality CR-10 -// https://www.aliexpress.com/item/32833148327.html +// BEEZ MINI 12864 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. // -// This is RAMPS-compatible using a single 10-pin connector. -// (For CR-10 owners who want to replace the Melzi Creality board but retain the display) +//#define BEEZ_MINI_12864 + +// +// Factory display for Creality CR-10 / CR-7 / Ender-3 +// https://marlinfw.org/docs/hardware/controllers.html#cr10_stockdisplay +// +// Connect to EXP1 on RAMPS and compatible boards. // //#define CR10_STOCKDISPLAY @@ -2834,14 +3188,14 @@ //#define ENDER2_STOCKDISPLAY // -// ANET and Tronxy Graphical Controller -// -// Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6 -// A clone of the RepRapDiscount full graphics display but with -// different pins/wiring (see pins_ANET_10.h). Enable one of these. +// ANET and Tronxy 128×64 Full Graphics Controller as used on Anet A6 // //#define ANET_FULL_GRAPHICS_LCD -//#define ANET_FULL_GRAPHICS_LCD_ALT_WIRING + +// +// GUCOCO CTC 128×64 Full Graphics Controller as used on GUCOCO CTC A10S +// +//#define CTC_A10S_A13 // // AZSMZ 12864 LCD with SD @@ -2890,14 +3244,14 @@ // // Tiny, but very sharp OLED display // -//#define MKS_12864OLED // Uses the SH1106 controller (default) +//#define MKS_12864OLED // Uses the SH1106 controller //#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller // // Zonestar OLED 128×64 Full Graphics Controller // //#define ZONESTAR_12864LCD // Graphical (DOGM) with ST7920 controller -//#define ZONESTAR_12864OLED // 1.3" OLED with SH1106 controller (default) +//#define ZONESTAR_12864OLED // 1.3" OLED with SH1106 controller //#define ZONESTAR_12864OLED_SSD1306 // 0.96" OLED with SSD1306 controller // @@ -2926,23 +3280,16 @@ /** * DGUS Touch Display with DWIN OS. (Choose one.) - * ORIGIN : https://www.aliexpress.com/item/32993409517.html - * FYSETC : https://www.aliexpress.com/item/32961471929.html - * MKS : https://www.aliexpress.com/item/1005002008179262.html - * - * Flash display with DGUS Displays for Marlin: - * - Format the SD card to FAT32 with an allocation size of 4kb. - * - Download files as specified for your type of display. - * - Plug the microSD card into the back of the display. - * - Boot the display and wait for the update to complete. * * ORIGIN (Marlin DWIN_SET) * - Download https://github.com/coldtobi/Marlin_DGUS_Resources * - Copy the downloaded DWIN_SET folder to the SD card. + * - Product: https://www.aliexpress.com/item/32993409517.html * * FYSETC (Supplier default) * - Download https://github.com/FYSETC/FYSTLCD-2.0 * - Copy the downloaded SCREEN folder to the SD card. + * - Product: https://www.aliexpress.com/item/32961471929.html * * HIPRECY (Supplier default) * - Download https://github.com/HiPrecy/Touch-Lcd-LEO @@ -2951,22 +3298,38 @@ * MKS (MKS-H43) (Supplier default) * - Download https://github.com/makerbase-mks/MKS-H43 * - Copy the downloaded DWIN_SET folder to the SD card. + * - Product: https://www.aliexpress.com/item/1005002008179262.html * * RELOADED (T5UID1) - * - Download https://github.com/Desuuuu/DGUS-reloaded/releases + * - Download https://github.com/Neo2003/DGUS-reloaded/releases * - Copy the downloaded DWIN_SET folder to the SD card. + * + * IA_CREALITY (T5UID1) + * - Download https://github.com/InsanityAutomation/Marlin/raw/CrealityDwin_2.0/TM3D_Combined480272_Landscape_V7.7z + * - Copy the downloaded DWIN_SET folder to the SD card. + * + * E3S1PRO (T5L) + * - Download https://github.com/CrealityOfficial/Ender-3S1/archive/3S1_Plus_Screen.zip + * - Copy the downloaded DWIN_SET folder to the SD card. + * + * Flash display with DGUS Displays for Marlin: + * - Format the SD card to FAT32 with an allocation size of 4kb. + * - Download files as specified for your type of display. + * - Plug the microSD card into the back of the display. + * - Boot the display and wait for the update to complete. + * + * :[ 'ORIGIN', 'FYSETC', 'HYPRECY', 'MKS', 'RELOADED', 'IA_CREALITY', 'E3S1PRO' ] */ -//#define DGUS_LCD_UI_ORIGIN -//#define DGUS_LCD_UI_FYSETC -//#define DGUS_LCD_UI_HIPRECY -//#define DGUS_LCD_UI_MKS -//#define DGUS_LCD_UI_RELOADED -#if ENABLED(DGUS_LCD_UI_MKS) +//#define DGUS_LCD_UI ORIGIN +#if DGUS_UI_IS(MKS) #define USE_MKS_GREEN_UI +#elif DGUS_UI_IS(IA_CREALITY) + //#define LCD_SCREEN_ROTATE 90 // Portrait Mode or 800x480 displays + //#define IA_CREALITY_BOOT_DELAY 1500 // (ms) #endif // -// Touch-screen LCD for Malyan M200/M300 printers +// LCD for Malyan M200/M300 printers // //#define MALYAN_LCD @@ -2977,14 +3340,28 @@ //#define TOUCH_UI_FTDI_EVE // -// Touch-screen LCD for Anycubic printers +// Touch-screen LCD for Anycubic Chiron +// +//#define ANYCUBIC_LCD_CHIRON + +// +// Touch-screen LCD for Anycubic i3 Mega // //#define ANYCUBIC_LCD_I3MEGA -//#define ANYCUBIC_LCD_CHIRON -#if EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) - //#define ANYCUBIC_LCD_DEBUG +#if ENABLED(ANYCUBIC_LCD_I3MEGA) + //#define ANYCUBIC_LCD_GCODE_EXT // Add ".gcode" to menu entries for DGUS clone compatibility #endif +// +// Touch-screen LCD for Anycubic Vyper +// +//#define ANYCUBIC_LCD_VYPER + +// +// Sovol SV-06 Resistive Touch Screen +// +//#define SOVOL_SV06_RTS + // // 320x240 Nextion 2.8" serial TFT Resistive Touch Screen NX3224T028 // @@ -3012,6 +3389,7 @@ // // 480x320, 3.5", SPI Display with Rotary Encoder from MKS // Usually paired with MKS Robin Nano V2 & V3 +// https://github.com/makerbase-mks/MKS-TFT-Hardware/tree/master/MKS%20TS35 // //#define MKS_TS35_V2_0 @@ -3051,7 +3429,7 @@ //#define MKS_ROBIN_TFT_V1_1R // -// 480x320, 3.5", FSMC Stock Display from TronxXY +// 480x320, 3.5", FSMC Stock Display from Tronxy // //#define TFT_TRONXY_X5SA @@ -3076,12 +3454,14 @@ //#define ANET_ET5_TFT35 // -// 1024x600, 7", RGB Stock Display with Rotary Encoder from BIQU-BX +// 1024x600, 7", RGB Stock Display with Rotary Encoder from BIQU BX +// https://github.com/bigtreetech/BIQU-BX/tree/master/Hardware // //#define BIQU_BX_TFT70 // // 480x320, 3.5", SPI Stock Display with Rotary Encoder from BIQU B1 SE Series +// https://github.com/bigtreetech/TFT35-SPI/tree/master/v1 // //#define BTT_TFT35_SPI_V1_0 @@ -3118,8 +3498,34 @@ //#define TFT_COLOR_UI //#define TFT_LVGL_UI +#if ENABLED(TFT_COLOR_UI) + /** + * TFT Font for Color UI. Choose one of the following: + * + * NOTOSANS - Default font with anti-aliasing. Supports Latin Extended and non-Latin characters. + * UNIFONT - Lightweight font, no anti-aliasing. Supports Latin Extended and non-Latin characters. + * HELVETICA - Lightweight font, no anti-aliasing. Supports Basic Latin (0x0020-0x007F) and Latin-1 Supplement (0x0080-0x00FF) characters only. + * :['NOTOSANS', 'UNIFONT', 'HELVETICA'] + */ + #define TFT_FONT NOTOSANS + + /** + * TFT Theme for Color UI. Choose one of the following or add a new one to 'Marlin/src/lcd/tft/themes' directory + * + * BLUE_MARLIN - Default theme with 'midnight blue' background + * BLACK_MARLIN - Theme with 'black' background + * ANET_BLACK - Theme used for Anet ET4/5 + * :['BLUE_MARLIN', 'BLACK_MARLIN', 'ANET_BLACK'] + */ + #define TFT_THEME BLACK_MARLIN + + //#define TFT_SHARED_IO // I/O is shared between TFT display and other devices. Disable async data transfer. + + #define COMPACT_MARLIN_BOOT_LOGO // Use compressed data to save Flash space +#endif + #if ENABLED(TFT_LVGL_UI) - //#define MKS_WIFI_MODULE // MKS WiFi module + //#define MKS_WIFI_MODULE // MKS WiFi module #endif /** @@ -3129,6 +3535,8 @@ * TFT_ROTATE_180, TFT_ROTATE_180_MIRROR_X, TFT_ROTATE_180_MIRROR_Y, * TFT_ROTATE_270, TFT_ROTATE_270_MIRROR_X, TFT_ROTATE_270_MIRROR_Y, * TFT_MIRROR_X, TFT_MIRROR_Y, TFT_NO_ROTATION + * + * :{ 'TFT_NO_ROTATION':'None', 'TFT_ROTATE_90':'90°', 'TFT_ROTATE_90_MIRROR_X':'90° (Mirror X)', 'TFT_ROTATE_90_MIRROR_Y':'90° (Mirror Y)', 'TFT_ROTATE_180':'180°', 'TFT_ROTATE_180_MIRROR_X':'180° (Mirror X)', 'TFT_ROTATE_180_MIRROR_Y':'180° (Mirror Y)', 'TFT_ROTATE_270':'270°', 'TFT_ROTATE_270_MIRROR_X':'270° (Mirror X)', 'TFT_ROTATE_270_MIRROR_Y':'270° (Mirror Y)', 'TFT_MIRROR_X':'Mirror X', 'TFT_MIRROR_Y':'Mirror Y' } */ //#define TFT_ROTATION TFT_NO_ROTATION @@ -3145,15 +3553,22 @@ //#define DWIN_MARLINUI_PORTRAIT // MarlinUI (portrait orientation) //#define DWIN_MARLINUI_LANDSCAPE // MarlinUI (landscape orientation) +#if ENABLED(DWIN_CREALITY_LCD) + //#define USE_STRING_HEADINGS // Use string headings for Creality UI instead of images + //#define USE_STRING_TITLES // Use string titles for Creality UI instead of images +#endif + // // Touch Screen Settings // //#define TOUCH_SCREEN #if ENABLED(TOUCH_SCREEN) - #define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens - #define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus + #define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens + #define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus - //#define TOUCH_IDLE_SLEEP 300 // (s) Turn off the TFT backlight if set (5mn) + #if ANY(TFT_CLASSIC_UI, TFT_COLOR_UI) + //#define NO_BACK_MENU_ITEM // Don't display a top menu item to go back to the parent menu + #endif #define TOUCH_SCREEN_CALIBRATION @@ -3163,7 +3578,7 @@ //#define TOUCH_OFFSET_Y 257 //#define TOUCH_ORIENTATION TOUCH_LANDSCAPE - #if BOTH(TOUCH_SCREEN_CALIBRATION, EEPROM_SETTINGS) + #if ALL(TOUCH_SCREEN_CALIBRATION, EEPROM_SETTINGS) #define TOUCH_CALIBRATION_AUTO_SAVE // Auto save successful calibration values to EEPROM #endif @@ -3177,7 +3592,9 @@ // https://reprapworld.com/products/electronics/ramps/keypad_v1_0_fully_assembled/ // //#define REPRAPWORLD_KEYPAD -//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // (mm) Distance to move per key-press +#if ENABLED(REPRAPWORLD_KEYPAD) + //#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // (mm) Distance to move per key-press +#endif // // EasyThreeD ET-4000+ with button input and status LED @@ -3194,22 +3611,26 @@ // :[1,2,3,4,5,6,7,8] //#define NUM_M106_FANS 1 -// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency -// which is not as annoying as with the hardware PWM. On the other hand, if this frequency -// is too low, you should also increment SOFT_PWM_SCALE. +/** + * Use software PWM to drive the fan, as for the heaters. This uses a very low frequency + * which is not as annoying as with the hardware PWM. On the other hand, if this frequency + * is too low, you should also increment SOFT_PWM_SCALE. + */ //#define FAN_SOFT_PWM -// Incrementing this by 1 will double the software PWM frequency, -// affecting heaters, and the fan if FAN_SOFT_PWM is enabled. -// However, control resolution will be halved for each increment; -// at zero value, there are 128 effective control positions. -// :[0,1,2,3,4,5,6,7] +/** + * Incrementing this by 1 will double the software PWM frequency, affecting heaters, and + * the fan if FAN_SOFT_PWM is enabled. However, control resolution will be halved for each + * increment; at zero value, there are 128 effective control positions. + * :[0,1,2,3,4,5,6,7] + */ #define SOFT_PWM_SCALE 0 -// If SOFT_PWM_SCALE is set to a value higher than 0, dithering can -// be used to mitigate the associated resolution loss. If enabled, -// some of the PWM cycles are stretched so on average the desired -// duty cycle is attained. +/** + * If SOFT_PWM_SCALE is set to a value higher than 0, dithering can be used to mitigate the + * associated resolution loss. If enabled, some of the PWM cycles are stretched so on average + * the desired duty cycle is attained. + */ //#define SOFT_PWM_DITHER // @section extras @@ -3219,9 +3640,11 @@ // @section lights -// Temperature status LEDs that display the hotend and bed temperature. -// If all hotends, bed temperature, and target temperature are under 54C -// then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) +/** + * Temperature status LEDs that display the hotend and bed temperature. + * If all hotends, bed temperature, and target temperature are under 54C + * the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) + */ //#define TEMP_STAT_LEDS // Support for BlinkM/CyzRgb @@ -3244,26 +3667,36 @@ * luminance values can be set from 0 to 255. * For NeoPixel LED an overall brightness parameter is also available. * - * *** CAUTION *** + * === CAUTION === * LED Strips require a MOSFET Chip between PWM lines and LEDs, * as the Arduino cannot handle the current the LEDs will require. * Failure to follow this precaution can destroy your Arduino! + * * NOTE: A separate 5V power supply is required! The NeoPixel LED needs * more current than the Arduino 5V linear regulator can produce. - * *** CAUTION *** * - * LED Type. Enable only one of the following two options. + * Requires PWM frequency between 50 <> 100Hz (Check HAL or variant) + * Use FAST_PWM_FAN, if possible, to reduce fan noise. */ + +// LED Type. Enable only one of the following two options: //#define RGB_LED //#define RGBW_LED -#if EITHER(RGB_LED, RGBW_LED) +#if ANY(RGB_LED, RGBW_LED) //#define RGB_LED_R_PIN 34 //#define RGB_LED_G_PIN 43 //#define RGB_LED_B_PIN 35 //#define RGB_LED_W_PIN -1 #endif +#if ANY(RGB_LED, RGBW_LED, PCA9632) + //#define RGB_STARTUP_TEST // For PWM pins, fade between all colors + #if ENABLED(RGB_STARTUP_TEST) + #define RGB_STARTUP_TEST_INNER_MS 10 // (ms) Reduce or increase fading speed + #endif +#endif + // Support for Adafruit NeoPixel LED driver //#define NEOPIXEL_LED #if ENABLED(NEOPIXEL_LED) @@ -3283,6 +3716,7 @@ #define NEOPIXEL2_PIXELS 15 // Number of LEDs in the second strip #define NEOPIXEL2_BRIGHTNESS 127 // Initial brightness (0-255) #define NEOPIXEL2_STARTUP_TEST // Cycle through colors at startup + #define NEOPIXEL_M150_DEFAULT -1 // Default strip for M150 without 'S'. Use -1 to set all by default. #else //#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel #endif @@ -3290,7 +3724,8 @@ // Use some of the NeoPixel LEDs for static (background) lighting //#define NEOPIXEL_BKGD_INDEX_FIRST 0 // Index of the first background LED //#define NEOPIXEL_BKGD_INDEX_LAST 5 // Index of the last background LED - //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W + //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W + //#define NEOPIXEL_BKGD_TIMEOUT_COLOR { 25, 25, 25, 0 } // R, G, B, W //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off #endif diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e5d23526db..e46a3af2de 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 02010100 +#define CONFIGURATION_ADV_H_VERSION 02010300 // @section develop @@ -47,8 +47,9 @@ * 2 = config.ini - File format for PlatformIO preprocessing. * 3 = schema.json - The entire configuration schema. (13 = pattern groups) * 4 = schema.yml - The entire configuration schema. + * 5 = Config.h - Minimal configuration by popular demand. */ -//#define CONFIG_EXPORT // :[1:'JSON', 2:'config.ini', 3:'schema.json', 4:'schema.yml'] +//#define CONFIG_EXPORT 105 // :[1:'JSON', 2:'config.ini', 3:'schema.json', 4:'schema.yml', 5:'Config.h'] //=========================================================================== //============================= Thermal Settings ============================ @@ -173,8 +174,10 @@ * Thermocouple Options — for MAX6675 (-2), MAX31855 (-3), and MAX31865 (-5). */ //#define TEMP_SENSOR_FORCE_HW_SPI // Ignore SCK/MOSI/MISO pins; use CS and the default SPI bus. -//#define MAX31865_SENSOR_WIRES_0 2 // (2-4) Number of wires for the probe connected to a MAX31865 board. -//#define MAX31865_SENSOR_WIRES_1 2 +//#define MAX31865_SENSOR_WIRES_0 2 // (2-4) Number of wires for the probe connected to a MAX31865 board. +//#define MAX31865_SENSOR_WIRES_1 2 +//#define MAX31865_SENSOR_WIRES_2 2 +//#define MAX31865_SENSOR_WIRES_BED 2 //#define MAX31865_50HZ_FILTER // Use a 50Hz filter instead of the default 60Hz. //#define MAX31865_USE_READ_ERROR_DETECTION // Treat value spikes (20°C delta in under 1s) as read errors. @@ -185,15 +188,15 @@ //#define MAX31865_WIRE_OHMS_0 0.95f // For 2-wire, set the wire resistances for more accurate readings. //#define MAX31865_WIRE_OHMS_1 0.0f +//#define MAX31865_WIRE_OHMS_2 0.0f +//#define MAX31865_WIRE_OHMS_BED 0.0f /** * Hephestos 2 24V heated bed upgrade kit. - * https://store.bq.com/en/heated-bed-kit-hephestos2 + * https://www.en3dstudios.com/product/bq-hephestos-2-heated-bed-kit/ */ //#define HEPHESTOS2_HEATED_BED_KIT #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) - #undef TEMP_SENSOR_BED - #define TEMP_SENSOR_BED 70 #define HEATER_BED_INVERTING true #endif @@ -202,7 +205,7 @@ // #if DISABLED(PIDTEMPBED) #define BED_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control - #if ENABLED(BED_LIMIT_SWITCHING) + #if ANY(BED_LIMIT_SWITCHING, PELTIER_BED) #define BED_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > BED_HYSTERESIS #endif #endif @@ -210,18 +213,19 @@ // // Heated Chamber options // -#if DISABLED(PIDTEMPCHAMBER) - #define CHAMBER_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control - #if ENABLED(CHAMBER_LIMIT_SWITCHING) - #define CHAMBER_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > CHAMBER_HYSTERESIS - #endif -#endif #if TEMP_SENSOR_CHAMBER //#define HEATER_CHAMBER_PIN P2_04 // Required heater on/off pin (example: SKR 1.4 Turbo HE1 plug) //#define HEATER_CHAMBER_INVERTING false //#define FAN1_PIN -1 // Remove the fan signal on pin P2_04 (example: SKR 1.4 Turbo HE1 plug) + #if DISABLED(PIDTEMPCHAMBER) + #define CHAMBER_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control + #if ENABLED(CHAMBER_LIMIT_SWITCHING) + #define CHAMBER_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > CHAMBER_HYSTERESIS + #endif + #endif + //#define CHAMBER_FAN // Enable a fan on the chamber #if ENABLED(CHAMBER_FAN) //#define CHAMBER_FAN_INDEX 2 // Index of a fan to repurpose as the chamber fan. (Default: first unused fan) @@ -276,9 +280,15 @@ #define THERMAL_PROTECTION_BOARD // Halt the printer if the board sensor leaves the temp range below. #define BOARD_MINTEMP 8 // (°C) #define BOARD_MAXTEMP 70 // (°C) - #ifndef TEMP_BOARD_PIN - //#define TEMP_BOARD_PIN -1 // Board temp sensor pin, if not set in pins file. - #endif + //#define TEMP_BOARD_PIN -1 // Board temp sensor pin override. +#endif + +// +// SoC Sensor options +// +#if TEMP_SENSOR_SOC + #define THERMAL_PROTECTION_SOC // Halt the printer if the SoC sensor leaves the temp range below. + #define SOC_MAXTEMP 85 // (°C) #endif /** @@ -287,7 +297,7 @@ * protect against a broken or disconnected thermistor wire. * * The issue: If a thermistor falls out, it will report the much lower - * temperature of the air in the room, and the the firmware will keep + * temperature of the air in the room, and the firmware will keep * the heater on. * * The solution: Once the temperature reaches the target, start observing. @@ -297,13 +307,16 @@ * If you get false positives for "Thermal Runaway", increase * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD */ -#if ENABLED(THERMAL_PROTECTION_HOTENDS) - #define THERMAL_PROTECTION_PERIOD 40 // Seconds - #define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius +#if ALL(HAS_HOTEND, THERMAL_PROTECTION_HOTENDS) + #define THERMAL_PROTECTION_PERIOD 40 // (seconds) + #define THERMAL_PROTECTION_HYSTERESIS 4 // (°C) - //#define ADAPTIVE_FAN_SLOWING // Slow part cooling fan if temperature drops - #if BOTH(ADAPTIVE_FAN_SLOWING, PIDTEMP) - //#define NO_FAN_SLOWING_IN_PID_TUNING // Don't slow fan speed during M303 + //#define ADAPTIVE_FAN_SLOWING // Slow down the part-cooling fan if the temperature drops + #if ENABLED(ADAPTIVE_FAN_SLOWING) + //#define REPORT_ADAPTIVE_FAN_SLOWING // Report fan slowing activity to the console + #if ANY(MPCTEMP, PIDTEMP) + //#define TEMP_TUNING_MAINTAIN_FAN // Don't slow down the fan speed during M303 or M306 T + #endif #endif /** @@ -318,76 +331,106 @@ * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set * below 2. */ - #define WATCH_TEMP_PERIOD 40 // Seconds - #define WATCH_TEMP_INCREASE 2 // Degrees Celsius + #define WATCH_TEMP_PERIOD 40 // (seconds) + #define WATCH_TEMP_INCREASE 2 // (°C) #endif /** * Thermal Protection parameters for the bed are just as above for hotends. */ -#if ENABLED(THERMAL_PROTECTION_BED) - #define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds - #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius +#if TEMP_SENSOR_BED && ENABLED(THERMAL_PROTECTION_BED) + #define THERMAL_PROTECTION_BED_PERIOD 20 // (seconds) + #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // (°C) /** * As described above, except for the bed (M140/M190/M303). */ - #define WATCH_BED_TEMP_PERIOD 60 // Seconds - #define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius + #define WATCH_BED_TEMP_PERIOD 60 // (seconds) + #define WATCH_BED_TEMP_INCREASE 2 // (°C) #endif /** * Thermal Protection parameters for the heated chamber. */ -#if ENABLED(THERMAL_PROTECTION_CHAMBER) - #define THERMAL_PROTECTION_CHAMBER_PERIOD 20 // Seconds - #define THERMAL_PROTECTION_CHAMBER_HYSTERESIS 2 // Degrees Celsius +#if TEMP_SENSOR_CHAMBER && ENABLED(THERMAL_PROTECTION_CHAMBER) + #define THERMAL_PROTECTION_CHAMBER_PERIOD 20 // (seconds) + #define THERMAL_PROTECTION_CHAMBER_HYSTERESIS 2 // (°C) /** * Heated chamber watch settings (M141/M191). */ - #define WATCH_CHAMBER_TEMP_PERIOD 60 // Seconds - #define WATCH_CHAMBER_TEMP_INCREASE 2 // Degrees Celsius + #define WATCH_CHAMBER_TEMP_PERIOD 60 // (seconds) + #define WATCH_CHAMBER_TEMP_INCREASE 2 // (°C) #endif /** * Thermal Protection parameters for the laser cooler. */ -#if ENABLED(THERMAL_PROTECTION_COOLER) - #define THERMAL_PROTECTION_COOLER_PERIOD 10 // Seconds - #define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // Degrees Celsius +#if TEMP_SENSOR_COOLER && ENABLED(THERMAL_PROTECTION_COOLER) + #define THERMAL_PROTECTION_COOLER_PERIOD 10 // (seconds) + #define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // (°C) /** * Laser cooling watch settings (M143/M193). */ - #define WATCH_COOLER_TEMP_PERIOD 60 // Seconds - #define WATCH_COOLER_TEMP_INCREASE 3 // Degrees Celsius + #define WATCH_COOLER_TEMP_PERIOD 60 // (seconds) + #define WATCH_COOLER_TEMP_INCREASE 3 // (°C) #endif #if ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_COOLER) /** - * Thermal Protection Variance Monitor - EXPERIMENTAL. - * Kill the machine on a stuck temperature sensor. Disable if you get false positives. + * Thermal Protection Variance Monitor - EXPERIMENTAL + * Kill the machine on a stuck temperature sensor. + * + * This feature may cause some thermally-stable systems to halt. Be sure to test it thoroughly under + * a variety of conditions. Disable if you get false positives. + * + * This feature ensures that temperature sensors are updating regularly. If sensors die or get "stuck", + * or if Marlin stops reading them, temperatures will remain constant while heaters may still be powered! + * This feature only monitors temperature changes so it should catch any issue, hardware or software. + * + * By default it uses the THERMAL_PROTECTION_*_PERIOD constants (above) for the time window, within which + * at least one temperature change must occur, to indicate that sensor polling is working. If any monitored + * heater's temperature remains totally constant (without even a fractional change) during this period, a + * thermal malfunction error occurs and the printer is halted. + * + * A very stable heater might produce a false positive and halt the printer. In this case, try increasing + * the corresponding THERMAL_PROTECTION_*_PERIOD constant a bit. Keep in mind that uncontrolled heating + * shouldn't be allowed to persist for more than a minute or two. + * + * Be careful to distinguish false positives from real sensor issues before disabling this feature. If the + * heater's temperature appears even slightly higher than expected after restarting, you may have a real + * thermal malfunction. Check the temperature graph in your host for any unusual bumps. */ - //#define THERMAL_PROTECTION_VARIANCE_MONITOR // Detect a sensor malfunction preventing temperature updates + //#define THERMAL_PROTECTION_VARIANCE_MONITOR + #if ENABLED(THERMAL_PROTECTION_VARIANCE_MONITOR) + // Variance detection window to override the THERMAL_PROTECTION...PERIOD settings above. + // Keep in mind that some heaters heat up faster than others. + //#define THERMAL_PROTECTION_VARIANCE_MONITOR_PERIOD 30 // (s) Override all watch periods + #endif #endif #if ENABLED(PIDTEMP) - // Add an experimental additional term to the heater power, proportional to the extrusion speed. + // Add an additional term to the heater power, proportional to the extrusion speed. // A well-chosen Kc value should add just enough power to melt the increased material volume. //#define PID_EXTRUSION_SCALING #if ENABLED(PID_EXTRUSION_SCALING) - #define DEFAULT_Kc (100) // heating power = Kc * e_speed #define LPQ_MAX_LEN 50 + #define DEFAULT_KC 100 // heating power = Kc * e_speed + #if ENABLED(PID_PARAMS_PER_HOTEND) + // Specify up to one value per hotend here, according to your setup. + // If there are fewer values, the last one applies to the remaining hotends. + #define DEFAULT_KC_LIST { DEFAULT_KC, DEFAULT_KC } // heating power = Kc * e_speed + #endif #endif /** - * Add an experimental additional term to the heater power, proportional to the fan speed. + * Add an additional term to the heater power, proportional to the fan speed. * A well-chosen Kf value should add just enough power to compensate for power-loss from the cooling fan. - * You can either just add a constant compensation with the DEFAULT_Kf value + * You can either just add a constant compensation with the DEFAULT_KF value * or follow the instruction below to get speed-dependent compensation. * - * Constant compensation (use only with fanspeeds of 0% and 100%) + * Constant compensation (use only with fan speeds of 0% and 100%) * --------------------------------------------------------------------- * A good starting point for the Kf-value comes from the calculation: * kf = (power_fan * eff_fan) / power_heater * 255 @@ -414,22 +457,27 @@ //#define PID_FAN_SCALING_ALTERNATIVE_DEFINITION #if ENABLED(PID_FAN_SCALING_ALTERNATIVE_DEFINITION) // The alternative definition is used for an easier configuration. - // Just figure out Kf at fullspeed (255) and PID_FAN_SCALING_MIN_SPEED. - // DEFAULT_Kf and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly. + // Just figure out Kf at full speed (255) and PID_FAN_SCALING_MIN_SPEED. + // DEFAULT_KF and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly. - #define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_Kf - #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf + #define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_KF + #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_KF #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING - #define DEFAULT_Kf (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED) - #define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_Kf)/255.0 + #define DEFAULT_KF (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED) + #define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_KF)/255.0 #else - #define PID_FAN_SCALING_LIN_FACTOR (0) // Power loss due to cooling = Kf * (fan_speed) - #define DEFAULT_Kf 10 // A constant value added to the PID-tuner + #define PID_FAN_SCALING_LIN_FACTOR (0) // Power-loss due to cooling = Kf * (fan_speed) + #define DEFAULT_KF 10 // A constant value added to the PID-tuner #define PID_FAN_SCALING_MIN_SPEED 10 // Minimum fan speed at which to enable PID_FAN_SCALING #endif #endif + #if ENABLED(PID_PARAMS_PER_HOTEND) + // Specify up to one value per hotend here, according to your setup. + // If there are fewer values, the last one applies to the remaining hotends. + #define DEFAULT_KF_LIST { DEFAULT_KF, DEFAULT_KF } + #endif #endif /** @@ -448,12 +496,15 @@ #define AUTOTEMP #if ENABLED(AUTOTEMP) #define AUTOTEMP_OLDWEIGHT 0.98 // Factor used to weight previous readings (0.0 < value < 1.0) + #define AUTOTEMP_MIN 210 + #define AUTOTEMP_MAX 250 + #define AUTOTEMP_FACTOR 0.1f // Turn on AUTOTEMP on M104/M109 by default using proportions set here //#define AUTOTEMP_PROPORTIONAL #if ENABLED(AUTOTEMP_PROPORTIONAL) - #define AUTOTEMP_MIN_P 0 // (°C) Added to the target temperature - #define AUTOTEMP_MAX_P 5 // (°C) Added to the target temperature - #define AUTOTEMP_FACTOR_P 1 // Apply this F parameter by default (overridden by M104/M109 F) + #define AUTOTEMP_MIN_P 0 // (°C) Added to the target temperature + #define AUTOTEMP_MAX_P 5 // (°C) Added to the target temperature + #define AUTOTEMP_FACTOR_P 1 // Apply this F parameter by default (overridden by M104/M109 F) #endif #endif @@ -467,10 +518,10 @@ * Thermistors able to support high temperature tend to have a hard time getting * good readings at room and lower temperatures. This means TEMP_SENSOR_X_RAW_LO_TEMP * will probably be caught when the heating element first turns on during the - * preheating process, which will trigger a min_temp_error as a safety measure + * preheating process, which will trigger a MINTEMP error as a safety measure * and force stop everything. * To circumvent this limitation, we allow for a preheat time (during which, - * min_temp_error won't be triggered) and add a min_temp buffer to handle + * MINTEMP error won't be triggered) and add a min_temp buffer to handle * aberrant readings. * * If you want to enable this feature for your hotend thermistor(s) @@ -478,21 +529,26 @@ */ // The number of consecutive low temperature errors that can occur -// before a min_temp_error is triggered. (Shouldn't be more than 10.) +// before a MINTEMP error is triggered. (Shouldn't be more than 10.) //#define MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED 0 -// The number of milliseconds a hotend will preheat before starting to check -// the temperature. This value should NOT be set to the time it takes the -// hot end to reach the target temperature, but the time it takes to reach -// the minimum temperature your thermistor can read. The lower the better/safer. -// This shouldn't need to be more than 30 seconds (30000) -//#define MILLISECONDS_PREHEAT_TIME 0 +/** + * The number of milliseconds a hotend will preheat before starting to check + * the temperature. This value should NOT be set to the time it takes the + * hot end to reach the target temperature, but the time it takes to reach + * the minimum temperature your thermistor can read. The lower the better/safer. + * This shouldn't need to be more than 30 seconds (30000) + */ +//#define PREHEAT_TIME_HOTEND_MS 0 +//#define PREHEAT_TIME_BED_MS 0 // @section extruder -// Extruder runout prevention. -// If the machine is idle and the temperature over MINTEMP -// then extrude some filament every couple of SECONDS. +/** + * Extruder runout prevention. + * If the machine is idle and the temperature over MINTEMP + * then extrude some filament every couple of SECONDS. + */ //#define EXTRUDER_RUNOUT_PREVENT #if ENABLED(EXTRUDER_RUNOUT_PREVENT) #define EXTRUDER_RUNOUT_MINTEMP 190 @@ -522,6 +578,8 @@ #define TEMP_SENSOR_AD8495_OFFSET 0.0 #define TEMP_SENSOR_AD8495_GAIN 1.0 +// @section fans + /** * Controller Fan * To cool down the stepper drivers and MOSFETs. @@ -532,6 +590,7 @@ //#define USE_CONTROLLER_FAN #if ENABLED(USE_CONTROLLER_FAN) //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan + //#define CONTROLLER_FAN2_PIN -1 // Set a custom pin for second controller fan //#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered //#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled. #define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.) @@ -542,16 +601,27 @@ // Use TEMP_SENSOR_BOARD as a trigger for enabling the controller fan //#define CONTROLLER_FAN_MIN_BOARD_TEMP 40 // (°C) Turn on the fan if the board reaches this temperature + // Use TEMP_SENSOR_SOC as a trigger for enabling the controller fan + //#define CONTROLLER_FAN_MIN_SOC_TEMP 40 // (°C) Turn on the fan if the SoC reaches this temperature + + #define CONTROLLER_FAN_BED_HEATING // Turn on the fan when heating the bed + //#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings #if ENABLED(CONTROLLER_FAN_EDITABLE) #define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu #endif #endif -// When first starting the main fan, run it at full speed for the -// given number of milliseconds. This gets the fan spinning reliably -// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu) -//#define FAN_KICKSTART_TIME 100 +/** + * Fan Kickstart + * When part cooling or controller fans first start, run at a speed that + * gets it spinning reliably for a short time before setting the requested speed. + * (Does not work on Sanguinololu with FAN_SOFT_PWM.) + */ +//#define FAN_KICKSTART_TIME 100 // (ms) +//#define FAN_KICKSTART_POWER 180 // 64-255 +//#define FAN_KICKSTART_LINEAR // Set kickstart time linearly based on the speed, e.g., for 20% (51) it will be FAN_KICKSTART_TIME * 0.2. + // Useful for quick speed up to low speed. Kickstart power must be set to 255. // Some coolers may require a non-zero "off" state. //#define FAN_OFF_PWM 1 @@ -580,7 +650,7 @@ * FAST_PWM_FAN_FREQUENCY * Set this to your desired frequency. * For AVR, if left undefined this defaults to F = F_CPU/(2*255*1) - * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. + * i.e., F = 31.4kHz on 16MHz micro-controllers or F = 39.2kHz on 20MHz micro-controllers. * For non AVR, if left undefined this defaults to F = 1Khz. * This F value is only to protect the hardware from an absence of configuration * and not to complete it when users are not aware that the frequency must be specifically set to support the target board. @@ -610,11 +680,12 @@ #endif /** - * Use one of the PWM fans as a redundant part-cooling fan + * Assign more PWM fans for part cooling, synchronized with Fan 0 */ -//#define REDUNDANT_PART_COOLING_FAN 2 // Index of the fan to sync with FAN 0. - -// @section extruder +//#define REDUNDANT_PART_COOLING_FAN 1 // Index of the first fan to synchronize with Fan 0 +#ifdef REDUNDANT_PART_COOLING_FAN + //#define NUM_REDUNDANT_FANS 1 // Number of sequential fans to synchronize with Fan 0 +#endif /** * Extruder cooling fans @@ -692,6 +763,7 @@ #define FANMUX2_PIN -1 /** + * @section caselight * M355 Case Light on-off / brightness */ //#define CASE_LIGHT_ENABLE @@ -706,17 +778,17 @@ #if ENABLED(NEOPIXEL_LED) //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light #endif - #if EITHER(RGB_LED, RGBW_LED) + #if ANY(RGB_LED, RGBW_LED) //#define CASE_LIGHT_USE_RGB_LED // Use RGB / RGBW LED as case light #endif - #if EITHER(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) + #if ANY(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) #define CASE_LIGHT_DEFAULT_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White } #endif #endif -// @section homing +// @section endstops -// If you want endstops to stay on (by default) even when not homing +// If you want endstops to stay on (by default) even when not homing, // enable this option. Override at any time with M120, M121. //#define ENDSTOPS_ALWAYS_ON_DEFAULT @@ -731,6 +803,8 @@ //#define CLOSED_LOOP_MOVE_COMPLETE_PIN -1 #endif +// @section idex + /** * Dual X Carriage * @@ -765,7 +839,6 @@ #define X1_MAX_POS X_BED_SIZE // A max coordinate so the X1 carriage can't hit the parked X2 carriage #define X2_MIN_POS 80 // A min coordinate so the X2 carriage can't hit the parked X1 carriage #define X2_MAX_POS 353 // The max position of the X2 carriage, typically also the home position - #define X2_HOME_DIR 1 // Set to 1. The X2 carriage always homes to the max endstop position #define X2_HOME_POS X2_MAX_POS // Default X2 home position. Set to X2_MAX_POS. // NOTE: For Dual X Carriage use M218 T1 Xn to override the X2_HOME_POS. // This allows recalibration of endstops distance without a rebuild. @@ -781,6 +854,8 @@ //#define EVENT_GCODE_IDEX_AFTER_MODECHANGE "G28X" #endif +// @section multi stepper + /** * Multi-Stepper / Multi-Endstop * @@ -799,22 +874,22 @@ * 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_) + * - Define the extra endstop pins here to override defaults. No auto-assignment. */ #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_STOP_PIN X_MAX_PIN // X2 endstop pin override #define X2_ENDSTOP_ADJUSTMENT 0 // X2 offset relative to X endstop #endif #endif -#if HAS_DUAL_Y_STEPPERS +#if HAS_Y2_STEPPER //#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_STOP_PIN Y_MAX_PIN // Y2 endstop pin override #define Y2_ENDSTOP_ADJUSTMENT 0 // Y2 offset relative to Y endstop #endif #endif @@ -827,21 +902,21 @@ //#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 + //#define Z2_STOP_PIN X_MAX_PIN // Z2 endstop pin override + #define Z2_ENDSTOP_ADJUSTMENT 0 // Z2 offset relative to Z 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 + //#define Z3_STOP_PIN Y_MAX_PIN // Z3 endstop pin override + #define Z3_ENDSTOP_ADJUSTMENT 0 // Z3 offset relative to Z 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 + //#define Z4_STOP_PIN Z_MAX_PIN // Z4 endstop pin override + #define Z4_ENDSTOP_ADJUSTMENT 0 // Z4 offset relative to Z endstop #endif #endif #endif @@ -852,6 +927,8 @@ //#define INVERT_E1_VS_E0_DIR // E direction signals are opposites #endif +// @section extruder + // Activate a solenoid on the active extruder with M380. Disable all with M381. // Define SOL0_PIN, SOL1_PIN, etc., for each extruder that has a solenoid. //#define EXT_SOLENOID @@ -870,10 +947,11 @@ #define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define HOMING_BACKOFF_POST_MM { 2, 2, 2 } // (linear=mm, rotational=°) Backoff from endstops after homing +//#define XY_COUNTERPART_BACKOFF_MM 0 // (mm) Backoff X after homing Y, and vice-versa //#define QUICK_HOME // If G28 contains XY do a diagonal move first //#define HOME_Y_BEFORE_X // If G28 contains XY home Y before X -//#define HOME_Z_FIRST // Home Z first. Requires a Z-MIN endstop (not a probe). +//#define HOME_Z_FIRST // Home Z first. Requires a real endstop (not a probe). //#define CODEPENDENT_XY_HOMING // If X/Y can't home without homing Y/X first // @section bltouch @@ -918,12 +996,15 @@ * Danger: Don't activate 5V mode unless attached to a 5V-tolerant controller! * V3.0 or 3.1: Set default mode to 5V mode at Marlin startup. * If disabled, OD mode is the hard-coded default on 3.0 - * On startup, Marlin will compare its eeprom to this value. If the selected mode - * differs, a mode set eeprom write will be completed at initialization. - * Use the option below to force an eeprom write to a V3.1 probe regardless. + * On startup, Marlin will compare its EEPROM to this value. If the selected mode + * differs, a mode set EEPROM write will be completed at initialization. + * Use the option below to force an EEPROM write to a V3.1 probe regardless. */ //#define BLTOUCH_SET_5V_MODE + // Safety: Enable voltage mode settings in the LCD menu. + //#define BLTOUCH_LCD_VOLTAGE_MENU + /** * Safety: Activate if connecting a probe with an unknown voltage mode. * V3.0: Set a probe into mode selected above at Marlin startup. Required for 5V mode on 3.0 @@ -942,12 +1023,16 @@ */ //#define BLTOUCH_HS_MODE true - // Safety: Enable voltage mode settings in the LCD menu. - //#define BLTOUCH_LCD_VOLTAGE_MENU + #ifdef BLTOUCH_HS_MODE + // The probe Z offset (M851 Z) is the height at which the probe triggers. + // This must be large enough to keep the probe pin off the bed and prevent + // it from snagging on the bed clips. + #define BLTOUCH_HS_EXTRA_CLEARANCE 7 // Extra Z Clearance + #endif #endif // BLTOUCH -// @section extras +// @section calibrate /** * Z Steppers Auto-Alignment @@ -1006,19 +1091,36 @@ #define G34_MAX_GRADE 5 // (%) Maximum incline that G34 will handle #define Z_STEPPER_ALIGN_ITERATIONS 5 // Number of iterations to apply during alignment #define Z_STEPPER_ALIGN_ACC 0.02 // Stop iterating early if the accuracy is better than this + #define RESTORE_LEVELING_AFTER_G34 // Restore leveling after G34 is done? + // After G34, re-home Z (G28 Z) or just calculate it from the last probe heights? // Re-homing might be more precise in reproducing the actual 'G28 Z' homing height, especially on an uneven bed. #define HOME_AFTER_G34 -#endif -// -// Add the G35 command to read bed corners to help adjust screws. Requires a bed probe. -// + /** + * Commands to execute at the start of G34 probing, + * after switching to the PROBING_TOOL. + */ + //#define EVENT_GCODE_BEFORE_G34 "M300 P440 S200" + + /** + * Commands to execute at the end of G34 probing. + * Useful to retract or move the Z probe out of the way. + */ + //#define EVENT_GCODE_AFTER_G34 "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" + +#endif // Z_STEPPER_AUTO_ALIGN + +/** + * Assisted Tramming + * + * Add the G35 command to measure bed corners and help adjust screws. Requires a bed probe. + */ //#define ASSISTED_TRAMMING #if ENABLED(ASSISTED_TRAMMING) - // Define positions for probe points. + // Define from 3 to 9 points to probe. #define TRAMMING_POINT_XY { { 20, 20 }, { 180, 20 }, { 180, 180 }, { 20, 180 } } // Define position names for probe points. @@ -1035,15 +1137,145 @@ //#define ASSISTED_TRAMMING_WAIT_POSITION { X_CENTER, Y_CENTER, 30 } // Move the nozzle out of the way for adjustment /** - * Screw thread: - * M3: 30 = Clockwise, 31 = Counter-Clockwise - * M4: 40 = Clockwise, 41 = Counter-Clockwise - * M5: 50 = Clockwise, 51 = Counter-Clockwise + * Screw Thread. Use one of the following defines: + * + * M3_CW = M3 Clockwise, M3_CCW = M3 Counter-Clockwise + * M4_CW = M4 Clockwise, M4_CCW = M4 Counter-Clockwise + * M5_CW = M5 Clockwise, M5_CCW = M5 Counter-Clockwise + * + * :{'M3_CW':'M3 Clockwise','M3_CCW':'M3 Counter-Clockwise','M4_CW':'M4 Clockwise','M4_CCW':'M4 Counter-Clockwise','M5_CW':'M5 Clockwise','M5_CCW':'M5 Counter-Clockwise'} */ - #define TRAMMING_SCREW_THREAD 30 + #define TRAMMING_SCREW_THREAD M3_CW #endif +// @section motion control + +/** + * Fixed-time-based Motion Control -- BETA FEATURE + * Enable/disable and set parameters with G-code M493 and M494. + * See ft_types.h for named values used by FTM options. + */ +//#define FT_MOTION +#if ENABLED(FT_MOTION) + //#define FTM_IS_DEFAULT_MOTION // Use FT Motion as the factory default? + //#define FT_MOTION_MENU // Provide a MarlinUI menu to set M493 and M494 parameters + + //#define NO_STANDARD_MOTION // Disable the standard motion system entirely to save Flash and RAM + #if DISABLED(NO_STANDARD_MOTION) + //#define FTM_HOME_AND_PROBE // Use FT Motion for homing / probing. Disable if FT Motion breaks these functions. + #endif + + //#define FTM_DYNAMIC_FREQ // Enable for linear adjustment of XY shaping frequency according to Z or E + #if ENABLED(FTM_DYNAMIC_FREQ) + #define FTM_DEFAULT_DYNFREQ_MODE dynFreqMode_DISABLED // Default mode of dynamic frequency calculation. (DISABLED, Z_BASED, MASS_BASED) + #endif + + // Disable unused shapers if you need more free space + #define FTM_SHAPER_ZV + #define FTM_SHAPER_ZVD + #define FTM_SHAPER_ZVDD + #define FTM_SHAPER_ZVDDD + #define FTM_SHAPER_EI + #define FTM_SHAPER_2HEI + #define FTM_SHAPER_3HEI + #define FTM_SHAPER_MZV + + #define FTM_DEFAULT_SHAPER_X ftMotionShaper_NONE // Default shaper mode on X axis (NONE, ZV, ZVD, ZVDD, ZVDDD, EI, 2HEI, 3HEI, MZV) + #define FTM_SHAPING_DEFAULT_FREQ_X 37.0f // (Hz) Default peak frequency used by input shapers + #define FTM_SHAPING_ZETA_X 0.1f // Zeta used by input shapers for X axis + #define FTM_SHAPING_V_TOL_X 0.05f // Vibration tolerance used by EI input shapers for X axis + + #define FTM_DEFAULT_SHAPER_Y ftMotionShaper_NONE // Default shaper mode on Y axis + #define FTM_SHAPING_DEFAULT_FREQ_Y 37.0f // (Hz) Default peak frequency used by input shapers + #define FTM_SHAPING_ZETA_Y 0.1f // Zeta used by input shapers for Y axis + #define FTM_SHAPING_V_TOL_Y 0.05f // Vibration tolerance used by EI input shapers for Y axis + + //#define FTM_SHAPER_Z // Include Z shaping support + #define FTM_DEFAULT_SHAPER_Z ftMotionShaper_NONE // Default shaper mode on Z axis + #define FTM_SHAPING_DEFAULT_FREQ_Z 21.0f // (Hz) Default peak frequency used by input shapers + #define FTM_SHAPING_ZETA_Z 0.03f // Zeta used by input shapers for Z axis + #define FTM_SHAPING_V_TOL_Z 0.05f // Vibration tolerance used by EI input shapers for Z axis + + //#define FTM_SHAPER_E // Include E shaping support + // Required to synchronize extruder with XYZ (better quality) + #define FTM_DEFAULT_SHAPER_E ftMotionShaper_NONE // Default shaper mode on Extruder axis + #define FTM_SHAPING_DEFAULT_FREQ_E 21.0f // (Hz) Default peak frequency used by input shapers + #define FTM_SHAPING_ZETA_E 0.03f // Zeta used by input shapers for E axis + #define FTM_SHAPING_V_TOL_E 0.05f // Vibration tolerance used by EI input shapers for E axis + + //#define FTM_RESONANCE_TEST // Sine sweep motion for resonance study + + //#define FTM_SMOOTHING // Smoothing can reduce artifacts and make steppers quieter + // on sharp corners, but too much will round corners. + #if ENABLED(FTM_SMOOTHING) + #define FTM_MAX_SMOOTHING_TIME 0.10f // (s) Maximum smoothing time. Higher values consume more RAM. + // Increase smoothing time to reduce jerky motion, ghosting and noises. + #define FTM_SMOOTHING_TIME_X 0.00f // (s) Smoothing time for X axis. Zero means disabled. + #define FTM_SMOOTHING_TIME_Y 0.00f // (s) Smoothing time for Y axis + #define FTM_SMOOTHING_TIME_Z 0.00f // (s) Smoothing time for Z axis + #define FTM_SMOOTHING_TIME_E 0.02f // (s) Smoothing time for E axis. Prevents noise/skipping from LA by + // smoothing acceleration peaks, which may also smooth curved surfaces. + #endif + + #define FTM_POLYS // Disable POLY5/6 to save ~3k of Flash. Preserves TRAPEZOIDAL. + #if ENABLED(FTM_POLYS) + #define FTM_TRAJECTORY_TYPE TRAPEZOIDAL // Block acceleration profile (TRAPEZOIDAL, POLY5, POLY6) + // TRAPEZOIDAL: Continuous Velocity. Max acceleration is respected. + // POLY5: Like POLY6 with 1.5x but uses less CPU. + // POLY6: Continuous Acceleration (aka S_CURVE). + // POLY trajectories not only reduce resonances without rounding corners, but also + // reduce extruder strain due to linear advance. + + #define FTM_POLY6_ACCELERATION_OVERSHOOT 1.875f // Max acceleration overshoot factor for POLY6 (1.25 to 1.875) + #endif + + /** + * Advanced configuration + */ + #define FTM_BUFFER_SIZE 128 // Window size for trajectory generation, must be a power of 2 (e.g 64, 128, 256, ...) + // The total buffered time in seconds is (FTM_BUFFER_SIZE/FTM_FS) + #define FTM_FS 1000 // (Hz) Frequency for trajectory generation. + #define FTM_MIN_SHAPE_FREQ 20 // (Hz) Minimum shaping frequency, lower consumes more RAM + +#endif // FT_MOTION + +/** + * Input Shaping + * + * Zero Vibration (ZV) Input Shaping for X and/or Y movements. + * + * This option uses a lot of SRAM for the step buffer. The buffer size is + * calculated automatically from SHAPING_FREQ_[XYZ], DEFAULT_AXIS_STEPS_PER_UNIT, + * DEFAULT_MAX_FEEDRATE and ADAPTIVE_STEP_SMOOTHING. The default calculation can + * be overridden by setting SHAPING_MIN_FREQ and/or SHAPING_MAX_FEEDRATE. + * The higher the frequency and the lower the feedrate, the smaller the buffer. + * If the buffer is too small at runtime, input shaping will have reduced + * effectiveness during high speed movements. + * + * Tune with M593 D F + */ +//#define INPUT_SHAPING_X +//#define INPUT_SHAPING_Y +//#define INPUT_SHAPING_Z +#if ANY(INPUT_SHAPING_X, INPUT_SHAPING_Y, INPUT_SHAPING_Z) + #if ENABLED(INPUT_SHAPING_X) + #define SHAPING_FREQ_X 40.0 // (Hz) The default dominant resonant frequency on the X axis. + #define SHAPING_ZETA_X 0.15 // Damping ratio of the X axis (range: 0.0 = no damping to 1.0 = critical damping). + #endif + #if ENABLED(INPUT_SHAPING_Y) + #define SHAPING_FREQ_Y 40.0 // (Hz) The default dominant resonant frequency on the Y axis. + #define SHAPING_ZETA_Y 0.15 // Damping ratio of the Y axis (range: 0.0 = no damping to 1.0 = critical damping). + #endif + #if ENABLED(INPUT_SHAPING_Z) + #define SHAPING_FREQ_Z 40.0 // (Hz) The default dominant resonant frequency on the Z axis. + #define SHAPING_ZETA_Z 0.15 // Damping ratio of the Z axis (range: 0.0 = no damping to 1.0 = critical damping). + #endif + //#define SHAPING_MIN_FREQ 20.0 // (Hz) By default the minimum of the shaping frequencies. Override to affect SRAM usage. + //#define SHAPING_MAX_STEPRATE 10000 // By default the maximum total step rate of the shaped axes. Override to affect SRAM usage. + //#define SHAPING_MENU // Add a menu to the LCD to set shaping parameters. +#endif + // @section motion #define AXIS_RELATIVE_MODES { false, false, false, false } @@ -1051,38 +1283,38 @@ // Add a Duplicate option for well-separated conjoined nozzles //#define MULTI_NOZZLE_DUPLICATION -// By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step. -#define INVERT_X_STEP_PIN false -#define INVERT_Y_STEP_PIN false -#define INVERT_Z_STEP_PIN false -#define INVERT_I_STEP_PIN false -#define INVERT_J_STEP_PIN false -#define INVERT_K_STEP_PIN false -#define INVERT_U_STEP_PIN false -#define INVERT_V_STEP_PIN false -#define INVERT_W_STEP_PIN false -#define INVERT_E_STEP_PIN false +// By default stepper drivers require an active-HIGH signal but some high-power drivers require an active-LOW signal to step. +#define STEP_STATE_X HIGH +#define STEP_STATE_Y HIGH +#define STEP_STATE_Z HIGH +#define STEP_STATE_I HIGH +#define STEP_STATE_J HIGH +#define STEP_STATE_K HIGH +#define STEP_STATE_U HIGH +#define STEP_STATE_V HIGH +#define STEP_STATE_W HIGH +#define STEP_STATE_E HIGH /** * Idle Stepper Shutdown - * Set DISABLE_INACTIVE_? 'true' to shut down axis steppers after an idle period. - * The Deactive Time can be overridden with M18 and M84. Set to 0 for No Timeout. + * Enable DISABLE_IDLE_* to shut down axis steppers after an idle period. + * The default timeout duration can be overridden with M18 and M84. Set to 0 for No Timeout. */ -#define DEFAULT_STEPPER_DEACTIVE_TIME 120 -#define DISABLE_INACTIVE_X true -#define DISABLE_INACTIVE_Y true -#define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part! -#define DISABLE_INACTIVE_I true -#define DISABLE_INACTIVE_J true -#define DISABLE_INACTIVE_K true -#define DISABLE_INACTIVE_U true -#define DISABLE_INACTIVE_V true -#define DISABLE_INACTIVE_W true -#define DISABLE_INACTIVE_E true +#define DEFAULT_STEPPER_TIMEOUT_SEC 120 +#define DISABLE_IDLE_X +#define DISABLE_IDLE_Y +#define DISABLE_IDLE_Z // Disable if the nozzle could fall onto your printed part! +//#define DISABLE_IDLE_I +//#define DISABLE_IDLE_J +//#define DISABLE_IDLE_K +//#define DISABLE_IDLE_U +//#define DISABLE_IDLE_V +//#define DISABLE_IDLE_W +#define DISABLE_IDLE_E // Shut down all idle extruders // Default Minimum Feedrates for printing and travel moves -#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum feedrate. Set with M205 S. -#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum travel feedrate. Set with M205 T. +#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s) Minimum feedrate. Set with M205 S. +#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s) Minimum travel feedrate. Set with M205 T. // Minimum time that a segment needs to take as the buffer gets emptied #define DEFAULT_MINSEGMENTTIME 20000 // (µs) Set with M205 B. @@ -1098,18 +1330,13 @@ * XY Frequency limit * Reduce resonance by limiting the frequency of small zigzag infill moves. * See https://hydraraptor.blogspot.com/2010/12/frequency-limit.html - * Use M201 F G to change limits at runtime. + * Use M201 F S to change limits at runtime. */ //#define XY_FREQUENCY_LIMIT 10 // (Hz) Maximum frequency of small zigzag infill moves. Set with M201 F. #ifdef XY_FREQUENCY_LIMIT - #define XY_FREQUENCY_MIN_PERCENT 5 // (percent) Minimum FR percentage to apply. Set with M201 G. + #define XY_FREQUENCY_MIN_PERCENT 5 // (%) Minimum FR percentage to apply. Set with M201 S. #endif -// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end -// of the buffer and all stops. This should not be much greater than zero and should only be changed -// if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05 // (mm/s) - // // Backlash Compensation // Adds extra movement to axes on direction-changes to account for backlash. @@ -1147,7 +1374,7 @@ #endif /** - * Automatic backlash, position and hotend offset calibration + * Automatic backlash, position, and hotend offset calibration * * Enable G425 to run automatic calibration using an electrically- * conductive cube, bolt, or washer mounted on the bed. @@ -1165,22 +1392,20 @@ //#define CALIBRATION_SCRIPT_PRE "M117 Starting Auto-Calibration\nT0\nG28\nG12\nM117 Calibrating..." //#define CALIBRATION_SCRIPT_POST "M500\nM117 Calibration data saved" - #define CALIBRATION_MEASUREMENT_RESOLUTION 0.01 // mm - - #define CALIBRATION_FEEDRATE_SLOW 60 // mm/min - #define CALIBRATION_FEEDRATE_FAST 1200 // mm/min - #define CALIBRATION_FEEDRATE_TRAVEL 3000 // mm/min + #define CALIBRATION_FEEDRATE_SLOW 60 // (mm/min) + #define CALIBRATION_FEEDRATE_FAST 1200 // (mm/min) + #define CALIBRATION_FEEDRATE_TRAVEL 3000 // (mm/min) // The following parameters refer to the conical section of the nozzle tip. - #define CALIBRATION_NOZZLE_TIP_HEIGHT 1.0 // mm - #define CALIBRATION_NOZZLE_OUTER_DIAMETER 2.0 // mm + #define CALIBRATION_NOZZLE_TIP_HEIGHT 1.0 // (mm) + #define CALIBRATION_NOZZLE_OUTER_DIAMETER 2.0 // (mm) - // Uncomment to enable reporting (required for "G425 V", but consumes PROGMEM). + // Uncomment to enable reporting (required for "G425 V", but consumes flash). //#define CALIBRATION_REPORTING // The true location and dimension the cube/bolt/washer on the bed. - #define CALIBRATION_OBJECT_CENTER { 264.0, -22.0, -2.0 } // mm - #define CALIBRATION_OBJECT_DIMENSIONS { 10.0, 10.0, 10.0 } // mm + #define CALIBRATION_OBJECT_CENTER { 264.0, -22.0, -2.0 } // (mm) + #define CALIBRATION_OBJECT_DIMENSIONS { 10.0, 10.0, 10.0 } // (mm) // Comment out any sides which are unreachable by the probe. For best // auto-calibration results, all sides must be reachable. @@ -1203,7 +1428,7 @@ //#define CALIBRATION_MEASURE_WMAX // Probing at the exact top center only works if the center is flat. If - // probing on a screwhead or hollow washer, probe near the edges. + // probing on a screw head or hollow washer, probe near the edges. //#define CALIBRATION_MEASURE_AT_TOP_EDGES // Define the pin to read during calibration @@ -1215,6 +1440,12 @@ #endif #endif +/** + * Multi-stepping sends steps in bursts to reduce MCU usage for high step-rates. + * This allows higher feedrates than the MCU could otherwise support. + */ +#define MULTISTEPPING_LIMIT 16 // :[1, 2, 4, 8, 16, 32, 64, 128] + /** * Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies * below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible @@ -1238,24 +1469,24 @@ #define MICROSTEP_MODES { 16, 16, 16, 16, 16, 16 } // [1,2,4,8,16] /** - * @section stepper motor current + * @section stepper motor current * - * Some boards have a means of setting the stepper motor current via firmware. + * Some boards have a means of setting the stepper motor current via firmware. * - * The power on motor currents are set by: - * PWM_MOTOR_CURRENT - used by MINIRAMBO & ULTIMAIN_2 - * known compatible chips: A4982 - * DIGIPOT_MOTOR_CURRENT - used by BQ_ZUM_MEGA_3D, RAMBO & SCOOVO_X9H - * known compatible chips: AD5206 - * DAC_MOTOR_CURRENT_DEFAULT - used by PRINTRBOARD_REVF & RIGIDBOARD_V2 - * known compatible chips: MCP4728 - * DIGIPOT_I2C_MOTOR_CURRENTS - used by 5DPRINT, AZTEEG_X3_PRO, AZTEEG_X5_MINI_WIFI, MIGHTYBOARD_REVE - * known compatible chips: MCP4451, MCP4018 + * The power on motor currents are set by: + * PWM_MOTOR_CURRENT - used by MINIRAMBO & ULTIMAIN_2 + * known compatible chips: A4982 + * DIGIPOT_MOTOR_CURRENT - used by BQ_ZUM_MEGA_3D, RAMBO & SCOOVO_X9H + * known compatible chips: AD5206 + * DAC_MOTOR_CURRENT_DEFAULT - used by PRINTRBOARD_REVF & RIGIDBOARD_V2 + * known compatible chips: MCP4728 + * DIGIPOT_I2C_MOTOR_CURRENTS - used by 5DPRINT, AZTEEG_X3_PRO, AZTEEG_X5_MINI_WIFI, MIGHTYBOARD_REVE + * known compatible chips: MCP4451, MCP4018 * - * Motor currents can also be set by M907 - M910 and by the LCD. - * M907 - applies to all. - * M908 - BQ_ZUM_MEGA_3D, RAMBO, PRINTRBOARD_REVF, RIGIDBOARD_V2 & SCOOVO_X9H - * M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2 + * Motor currents can also be set by M907 - M910 and by the LCD. + * M907 - applies to all. + * M908 - BQ_ZUM_MEGA_3D, RAMBO, PRINTRBOARD_REVF, RIGIDBOARD_V2 & SCOOVO_X9H + * M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2 */ //#define PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // Values in milliamps //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) @@ -1266,7 +1497,7 @@ */ //#define DIGIPOT_MCP4018 // Requires https://github.com/felias-fogg/SlowSoftI2CMaster //#define DIGIPOT_MCP4451 -#if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) +#if ANY(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT:4 AZTEEG_X3_PRO:8 MKS_SBASE:5 MIGHTYBOARD_REVE:5 // Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS. @@ -1295,12 +1526,16 @@ // @section lcd +// Turn off the display blinking that warns about possible accuracy reduction +//#define DISABLE_REDUCED_ACCURACY_WARNING + #if HAS_MANUAL_MOVE_MENU #define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel #define FINE_MANUAL_MOVE 0.025 // (mm) Smallest manual move (< 0.1mm) applying to Z on most machines #if IS_ULTIPANEL #define MANUAL_E_MOVES_RELATIVE // Display extruder move distance rather than "position" #define ULTIPANEL_FEEDMULTIPLY // Encoder sets the feedrate multiplier on the Status Screen + //#define ULTIPANEL_FLOWPERCENT // Encoder sets the flow percentage on the Status Screen #endif #endif @@ -1318,13 +1553,17 @@ #define FEEDRATE_CHANGE_BEEP_FREQUENCY 440 #endif -// -// LCD Backlight Timeout -// -//#define LCD_BACKLIGHT_TIMEOUT 30 // (s) Timeout before turning off the backlight - -#if HAS_BED_PROBE && EITHER(HAS_MARLINUI_MENU, HAS_TFT_LVGL_UI) - //#define PROBE_OFFSET_WIZARD // Add a Probe Z Offset calibration option to the LCD menu +/** + * Probe Offset Wizard + * Add a Probe Z Offset calibration option to the LCD menu. + * Use this helper to get a perfect 'M851 Z' probe offset. + * When launched this powerful wizard: + * - Measures the bed height at the configured position with the probe. + * - Moves the nozzle to the same position for a "paper" measurement. + * - The difference is used to set the probe Z offset. + */ +#if HAS_BED_PROBE && ANY(HAS_MARLINUI_MENU, HAS_TFT_LVGL_UI) + //#define PROBE_OFFSET_WIZARD #if ENABLED(PROBE_OFFSET_WIZARD) /** * Enable to init the Probe Z-Offset when starting the Wizard. @@ -1341,6 +1580,10 @@ #if HAS_MARLINUI_MENU #if HAS_BED_PROBE + + // Show Deploy / Stow Probe options in the Motion menu. + #define PROBE_DEPLOY_STOW_MENU + // Add calibration in the Probe Offsets menu to compensate for X-axis twist. //#define X_AXIS_TWIST_COMPENSATION #if ENABLED(X_AXIS_TWIST_COMPENSATION) @@ -1355,40 +1598,91 @@ #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 //#define LCD_INFO_MENU #if ENABLED(LCD_INFO_MENU) //#define LCD_PRINTER_INFO_IS_BOOTSCREEN // Show bootscreen(s) instead of Printer Info pages + //#define BUILD_INFO_MENU_ITEM // Add a menu item to display the build date and time #endif + /** + * MarlinUI "Move Axis" menu distances. Comma-separated list. + * Values are displayed as-defined, so always use plain numbers here. + * Axis moves <= 1/2 the axis length and Extruder moves <= EXTRUDE_MAXLENGTH + * will be shown in the move submenus. + */ + + #define MANUAL_MOVE_DISTANCE_MM 10, 1.0, 0.1 // (mm) + //#define MANUAL_MOVE_DISTANCE_MM 100, 50, 10, 1.0, 0.1 // (mm) + //#define MANUAL_MOVE_DISTANCE_MM 500, 100, 50, 10, 1.0, 0.1 // (mm) + + // Manual move distances for INCH_MODE_SUPPORT + #define MANUAL_MOVE_DISTANCE_IN 0.100, 0.010, 0.001 // (in) + //#define MANUAL_MOVE_DISTANCE_IN 1.000, 0.500, 0.100, 0.010, 0.001 // (in) + //#define MANUAL_MOVE_DISTANCE_IN 5.000, 1.000, 0.500, 0.100, 0.010, 0.001 // (in) + + // Manual move distances for rotational axes + #define MANUAL_MOVE_DISTANCE_DEG 90, 45, 22.5, 5, 1 // (°) + // BACK menu items keep the highlight at the top //#define TURBO_BACK_MENU_ITEM + // BACK menu items show "Back" instead of the previous menu name + //#define GENERIC_BACK_MENU_ITEM + // Insert a menu for preheating at the top level to allow for quick access //#define PREHEAT_SHORTCUT_MENU_ITEM + // Add Configuration > Debug Menu > Endstop Test for endstop/probe/runout testing + //#define LCD_ENDSTOP_TEST + #endif // HAS_MARLINUI_MENU -#if ANY(HAS_DISPLAY, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) - //#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) - // The timeout to return to the status screen from sub-menus - //#define LCD_TIMEOUT_TO_STATUS 15000 // (ms) - +#if HAS_DISPLAY + /** + * *** VENDORS PLEASE READ *** + * + * Marlin allows you to add a custom boot image for Graphical LCDs. + * With this option Marlin will first show your custom screen followed + * by the standard Marlin logo with version number and web URL. + * + * We encourage you to take advantage of this new feature and we also + * respectfully request that you retain the unmodified Marlin boot screen. + */ + #define SHOW_BOOTSCREEN // Show the Marlin bootscreen on startup. ** ENABLE FOR PRODUCTION ** #if ENABLED(SHOW_BOOTSCREEN) - #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) - #if EITHER(HAS_MARLINUI_U8GLIB, TFT_COLOR_UI) + #define BOOTSCREEN_TIMEOUT 3000 // (ms) Total Duration to display the boot screen(s) + #if ANY(HAS_MARLINUI_U8GLIB, TFT_COLOR_UI) #define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving lots of flash) #endif + #if HAS_MARLINUI_U8GLIB + //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of flash. + #endif + #if ANY(HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE, HAS_MARLINUI_HD44780, HAS_GRAPHICAL_TFT) + //#define SHOW_CUSTOM_BOOTSCREEN // Show the bitmap in Marlin/_Bootscreen.h on startup. + #endif #endif + #if HAS_MARLINUI_U8GLIB + //#define CUSTOM_STATUS_SCREEN_IMAGE // Show the bitmap in Marlin/_Statusscreen.h on the status screen. + #endif + + //#define SOUND_MENU_ITEM // Add a mute option to the LCD menu + #define SOUND_ON_DEFAULT // Buzzer/speaker default enabled state + + #if ENABLED(U8GLIB_SSD1309) + //#define LCD_DOUBLE_BUFFER // Optimize display updates. Costs ~1K of SRAM. + #endif + + #if HAS_WIRED_LCD + //#define DOUBLE_LCD_FRAMERATE // Not recommended for slow boards. + #endif + + // The timeout to return to the status screen from sub-menus + //#define LCD_TIMEOUT_TO_STATUS 15000 // (ms) + // Scroll a longer status message into view //#define STATUS_MESSAGE_SCROLLING @@ -1398,12 +1692,12 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY - // Add an 'M73' G-code to set the current percentage - //#define LCD_SET_PROGRESS_MANUALLY - // Show the E position (filament used) during printing //#define LCD_SHOW_E_TOTAL + // Display a negative temperature instead of "err" + //#define SHOW_TEMPERATURE_BELOW_ZERO + /** * LED Control Menu * Add LED Control to the LCD menu @@ -1421,44 +1715,62 @@ //#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup #endif #if ENABLED(NEO2_COLOR_PRESETS) - #define NEO2_USER_PRESET_RED 255 // User defined RED value - #define NEO2_USER_PRESET_GREEN 128 // User defined GREEN value - #define NEO2_USER_PRESET_BLUE 0 // User defined BLUE value - #define NEO2_USER_PRESET_WHITE 255 // User defined WHITE value - #define NEO2_USER_PRESET_BRIGHTNESS 255 // User defined intensity - //#define NEO2_USER_PRESET_STARTUP // Have the printer display the user preset color on startup for the second strip + #define NEO2_USER_PRESET_RED 255 // User defined RED value + #define NEO2_USER_PRESET_GREEN 128 // User defined GREEN value + #define NEO2_USER_PRESET_BLUE 0 // User defined BLUE value + #define NEO2_USER_PRESET_WHITE 255 // User defined WHITE value + #define NEO2_USER_PRESET_BRIGHTNESS 255 // User defined intensity + //#define NEO2_USER_PRESET_STARTUP // Have the printer display the user preset color on startup for the second strip #endif #endif +#endif // HAS_DISPLAY + +// Some displays offer Feedrate / Flow editing. +#if ANY(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN, ULTIPANEL_FEEDMULTIPLY) + #define SPEED_EDIT_MIN 10 // (%) Feedrate percentage edit range minimum + #define SPEED_EDIT_MAX 999 // (%) Feedrate percentage edit range maximum +#endif +#if ANY(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN) + #define FLOW_EDIT_MIN 10 // (%) Flow percentage edit range minimum + #define FLOW_EDIT_MAX 999 // (%) Flow percentage edit range maximum #endif -// LCD Print Progress options -#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) - #if CAN_SHOW_REMAINING_TIME - //#define SHOW_REMAINING_TIME // Display estimated time to completion - #if ENABLED(SHOW_REMAINING_TIME) - //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation - //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time - #endif +// Add 'M73' to set print job progress, overrides Marlin's built-in estimate +//#define SET_PROGRESS_MANUALLY +#if ENABLED(SET_PROGRESS_MANUALLY) + #define SET_PROGRESS_PERCENT // Add 'P' parameter to set percentage done + #define SET_REMAINING_TIME // Add 'R' parameter to set remaining time + //#define SET_INTERACTION_TIME // Add 'C' parameter to set time until next filament change or other user interaction + //#define M73_REPORT // Report M73 values to host + #if ALL(M73_REPORT, HAS_MEDIA) + #define M73_REPORT_SD_ONLY // Report only when printing from SD #endif +#endif - #if EITHER(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI) - //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits +// LCD Print Progress options. Multiple times may be displayed in turn. +#if HAS_DISPLAY && ANY(HAS_MEDIA, SET_PROGRESS_MANUALLY) + #define SHOW_PROGRESS_PERCENT // Show print progress percentage (doesn't affect progress bar) + #define SHOW_ELAPSED_TIME // Display elapsed printing time (prefix 'E') + //#define SHOW_REMAINING_TIME // Display estimated time to completion (prefix 'R') + #if ENABLED(SET_INTERACTION_TIME) + #define SHOW_INTERACTION_TIME // Display time until next user interaction ('C' = filament change) #endif + //#define PRINT_PROGRESS_SHOW_DECIMALS // Show/report progress with decimal digits, not all UIs support this - #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + #if ANY(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) //#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing #if ENABLED(LCD_PROGRESS_BAR) #define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar #define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message - #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) + #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) //#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it //#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar #endif #endif #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA /** * SD Card SPI Speed * May be required to resolve "volume init" errors. @@ -1493,6 +1805,7 @@ //#define NO_SD_AUTOSTART // Remove auto#.g file support completely to save some Flash, SRAM //#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files + //#define ONE_CLICK_PRINT // Prompt to print the newest file on inserted media //#define BROWSE_MEDIA_ON_INSERT // Open the file browser when media is inserted //#define MEDIA_MENU_AT_TOP // Force the media menu to be listed on the top of the main menu @@ -1503,6 +1816,14 @@ #define PE_LEDS_COMPLETED_TIME (30*60) // (seconds) Time to keep the LED "done" color before restoring normal illumination #endif + /** + * Priming for the Remaining Time estimate + * Long processes at the start of a G-code file can skew the Remaining Time estimate. + * Enable these options to start this estimation at a later point in the G-code file. + */ + //#define REMAINING_TIME_PRIME // Provide G-code 'M75 R' to prime the Remaining Time estimate + //#define REMAINING_TIME_AUTOPRIME // Prime the Remaining Time estimate later (e.g., at the end of 'M109') + /** * Continue after Power-Loss (Creality3D) * @@ -1513,19 +1834,27 @@ */ //#define POWER_LOSS_RECOVERY #if ENABLED(POWER_LOSS_RECOVERY) - #define PLR_ENABLED_DEFAULT false // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500) - //#define BACKUP_POWER_SUPPLY // Backup power / UPS to move the steppers on power loss - //#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS) - //#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module. - //#define POWER_LOSS_STATE HIGH // State of pin indicating power loss - //#define POWER_LOSS_PULLUP // Set pullup / pulldown as appropriate for your sensor + #define PLR_ENABLED_DEFAULT false // Power-Loss Recovery enabled by default. (Set with 'M413 Sn' & M500) + //#define PLR_HEAT_BED_ON_REBOOT // Heat up bed immediately on reboot to mitigate object detaching/warping. + //#define PLR_HEAT_BED_EXTRA 0 // (°C) Relative increase of bed temperature for better adhesion (limited by max temp). + //#define PLR_BED_THRESHOLD BED_MAXTEMP // (°C) Skip user confirmation at or above this bed temperature (0 to disable) + + //#define POWER_LOSS_PIN 44 // Pin to detect power-loss. Set to -1 to disable default pin on boards without module, or comment to use board default. + //#define POWER_LOSS_STATE HIGH // State of pin indicating power-loss + //#define POWER_LOSS_PULLUP // Set pullup / pulldown as appropriate for your sensor //#define POWER_LOSS_PULLDOWN - //#define POWER_LOSS_PURGE_LEN 20 // (mm) Length of filament to purge on resume - //#define POWER_LOSS_RETRACT_LEN 10 // (mm) Length of filament to retract on fail. Requires backup power. + + //#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power-loss with UPS) + //#define POWER_LOSS_PURGE_LEN 20 // (mm) Length of filament to purge on resume // Without a POWER_LOSS_PIN the following option helps reduce wear on the SD card, // especially with "vase mode" printing. Set too high and vases cannot be continued. - #define POWER_LOSS_MIN_Z_CHANGE 0.05 // (mm) Minimum Z change before saving power-loss data + #define POWER_LOSS_MIN_Z_CHANGE 0.05 // (mm) Minimum Z change before saving power-loss data + + //#define BACKUP_POWER_SUPPLY // Backup power / UPS to move the steppers on power-loss + #if ENABLED(BACKUP_POWER_SUPPLY) + //#define POWER_LOSS_RETRACT_LEN 10 // (mm) Length of filament to retract on fail + #endif // Enable if Z homing is needed for proper recovery. 99.9% of the time this should be disabled! //#define POWER_LOSS_RECOVER_ZHOME @@ -1561,15 +1890,21 @@ // SD Card Sorting options #if ENABLED(SDCARD_SORT_ALPHA) - #define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each. - #define FOLDER_SORTING -1 // -1=above 0=none 1=below - #define SDSORT_GCODE false // Allow turning sorting on/off with LCD and M34 G-code. - #define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting. - #define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.) - #define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option. - #define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use! - #define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting. - // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM. + #define SDSORT_QUICK true // Use Quick Sort as a sorting algorithm. Otherwise use Bubble Sort. + #define SDSORT_REVERSE false // Default to sorting file names in reverse order. + #define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each. + #define SDSORT_FOLDERS -1 // -1=above 0=none 1=below + #define SDSORT_GCODE false // Enable G-code M34 to set sorting behaviors: M34 S<-1|0|1> F<-1|0|1> + #define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.) + #define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting. + #if ENABLED(SDSORT_USES_RAM) + #define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option. + #if ENABLED(SDSORT_CACHE_NAMES) + #define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use! + #define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting. + // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM. + #endif + #endif #endif // Allow international symbols in long filenames. To display correctly, the @@ -1578,6 +1913,7 @@ //#define LONG_FILENAME_HOST_SUPPORT // Get the long filename of a file/folder with 'M33 ' and list long filenames with 'M20 L' //#define LONG_FILENAME_WRITE_SUPPORT // Create / delete files with long filenames via M28, M30, and Binary Transfer Protocol + //#define M20_TIMESTAMP_SUPPORT // Include timestamps by adding the 'T' flag to M20 commands //#define SCROLL_LONG_FILENAMES // Scroll long filenames in the SD card menu @@ -1607,7 +1943,7 @@ * * SCLK, MOSI, MISO --> SCLK, MOSI, MISO * INT --> SD_DETECT_PIN [1] - * SS --> SDSS + * SS --> SD_SS_PIN * * [1] On AVR an interrupt-capable pin is best for UHS3 compatibility. */ @@ -1634,7 +1970,7 @@ //#define USE_OTG_USB_HOST #if DISABLED(USE_OTG_USB_HOST) - #define USB_CS_PIN SDSS + #define USB_CS_PIN SD_SS_PIN #define USB_INTR_PIN SD_DETECT_PIN #endif #endif @@ -1671,6 +2007,9 @@ //#define CUSTOM_FIRMWARE_UPLOAD #endif + // "Over-the-air" Firmware Update with M936 - Required to set EEPROM flag + //#define OTA_FIRMWARE_UPDATE + /** * Set this option to one of the following (or the board's defaults apply): * @@ -1693,11 +2032,11 @@ #if ENABLED(MULTI_VOLUME) #define VOLUME_SD_ONBOARD #define VOLUME_USB_FLASH_DRIVE - #define DEFAULT_VOLUME SV_SD_ONBOARD - #define DEFAULT_SHARED_VOLUME SV_USB_FLASH_DRIVE + #define DEFAULT_VOLUME SD_ONBOARD // :[ 'SD_ONBOARD', 'USB_FLASH_DRIVE' ] + #define DEFAULT_SHARED_VOLUME USB_FLASH_DRIVE // :[ 'SD_ONBOARD', 'USB_FLASH_DRIVE' ] #endif -#endif // SDSUPPORT +#endif // HAS_MEDIA /** * By default an onboard SD card reader may be shared as a USB mass- @@ -1730,17 +2069,6 @@ // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_SMALL_INFOFONT - /** - * Graphical Display Sleep - * - * The U8G library provides sleep / wake functions for SH1106, SSD1306, - * SSD1309, and some other DOGM displays. - * Enable this option to save energy and prevent OLED pixel burn-in. - * Adds the menu item Configuration > LCD Timeout (m) to set a wait period - * from 0 (disabled) to 99 minutes. - */ - //#define DISPLAY_SLEEP_MINUTES 2 // (minutes) Timeout before turning off the screen - /** * ST7920-based LCDs can emulate a 16 x 4 character display using * the ST7920 character-generator for very fast screen updates. @@ -1756,7 +2084,7 @@ #if IS_U8GLIB_ST7920 // Enable this option and reduce the value to optimize screen updates. // The normal delay is 10µs. Use the lowest value that still gives a reliable display. - //#define DOGM_SPI_DELAY_US 5 + //#define DOGM_SPI_DELAY_US 5 // (µs) Delay after each SPI transfer //#define LIGHTWEIGHT_UI #if ENABLED(LIGHTWEIGHT_UI) @@ -1765,7 +2093,7 @@ #endif /** - * Status (Info) Screen customizations + * Status (Info) Screen customization * These options may affect code size and screen render time. * Custom status screens can forcibly override these settings. */ @@ -1781,26 +2109,22 @@ //#define STATUS_ALT_BED_BITMAP // Use the alternative bed bitmap //#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap //#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames + + // Only one STATUS_HEAT_* option can be enabled //#define STATUS_HEAT_PERCENT // Show heating in a progress bar - //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of flash. + //#define STATUS_HEAT_POWER // Show heater output power as a vertical bar + +#endif // HAS_MARLINUI_U8GLIB + +#if HAS_MARLINUI_U8GLIB || IS_DWIN_MARLINUI + #define MENU_HOLLOW_FRAME // Enable to save many cycles by drawing a hollow frame on Menu Screens + //#define OVERLAY_GFX_REVERSE // Swap the CW/CCW indicators in the graphics overlay // Frivolous Game Options //#define MARLIN_BRICKOUT //#define MARLIN_INVADERS //#define MARLIN_SNAKE //#define GAMES_EASTER_EGG // Add extra blank lines above the "Games" sub-menu - -#endif // HAS_MARLINUI_U8GLIB - -#if HAS_MARLINUI_U8GLIB || IS_DWIN_MARLINUI - // Show SD percentage next to the progress bar - //#define SHOW_SD_PERCENT - - // Enable to save many cycles by drawing a hollow frame on Menu Screens - #define MENU_HOLLOW_FRAME - - // Swap the CW/CCW indicators in the graphics overlay - //#define OVERLAY_GFX_REVERSE #endif // @@ -1815,11 +2139,11 @@ #define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates - #if ANY(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS, DGUS_LCD_UI_HIPRECY) + #if DGUS_UI_IS(FYSETC, MKS, HIPRECY) #define DGUS_PRINT_FILENAME // Display the filename during printing #define DGUS_PREHEAT_UI // Display a preheat screen during heatup - #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS) + #if DGUS_UI_IS(FYSETC, MKS) //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for FYSETC and MKS #else #define DGUS_UI_MOVE_DIS_OPTION // Enabled by default for UI_HIPRECY @@ -1836,6 +2160,22 @@ #define DGUS_UI_WAITING_STATUS 10 #define DGUS_UI_WAITING_STATUS_PERIOD 8 // Increase to slower waiting status looping #endif + + #elif DGUS_UI_IS(E3S1PRO) + /** + * The stock Ender-3 S1 Pro/Plus display firmware has rather poor SD file handling. + * + * The autoscroll is mainly useful for status messages, filenames, and the "About" page. + * + * NOTE: The Advanced SD Card option is affected by the stock touchscreen firmware, so + * pages 5 and up will display "4/4". This may get fixed in a screen firmware update. + */ + #define DGUS_SOFTWARE_AUTOSCROLL // Enable long text software auto-scroll + #define DGUS_AUTOSCROLL_START_CYCLES 1 // Refresh cycles without scrolling at the beginning of text strings + #define DGUS_AUTOSCROLL_END_CYCLES 1 // ... at the end of text strings + + #define DGUS_ADVANCED_SDCARD // Allow more than 20 files and navigating directories + #define DGUS_USERCONFIRM // Reuse the SD Card page to show various messages #endif #endif // HAS_DGUS_LCD @@ -1867,7 +2207,7 @@ // // Specify additional languages for the UI. Default specified by LCD_LANGUAGE. // -#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE, IS_DWIN_MARLINUI) +#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE, IS_DWIN_MARLINUI, ANYCUBIC_LCD_VYPER) //#define LCD_LANGUAGE_2 fr //#define LCD_LANGUAGE_3 de //#define LCD_LANGUAGE_4 es @@ -1963,7 +2303,7 @@ // Developer menu (accessed by touching "About Printer" copyright text) //#define TOUCH_UI_DEVELOPER_MENU -#endif +#endif // TOUCH_UI_FTDI_EVE // // Classic UI Options @@ -1977,13 +2317,31 @@ //#define TFT_BTOKMENU_COLOR 0x145F // 00010 100010 11111 Cyan #endif +/** + * Display Sleep + * Enable this option to save energy and prevent OLED pixel burn-in. + */ +//#define DISPLAY_SLEEP_MINUTES 2 // (minutes) Timeout before turning off the screen + +/** + * LCD Backlight Timeout + * Requires a display with a controllable backlight + */ +//#define LCD_BACKLIGHT_TIMEOUT_MINS 1 // (minutes) Timeout before turning off the backlight + +#if defined(DISPLAY_SLEEP_MINUTES) || defined(LCD_BACKLIGHT_TIMEOUT_MINS) + #define EDITABLE_DISPLAY_TIMEOUT // Edit sleep / backlight timeout with M255 S and a menu item +#endif + // // ADC Button Debounce // #if HAS_ADC_BUTTONS - #define ADC_BUTTON_DEBOUNCE_DELAY 16 // Increase if buttons bounce or repeat too fast + #define ADC_BUTTON_DEBOUNCE_DELAY 16 // (count) Increase if buttons bounce or repeat too fast #endif +//#define FAST_BUTTON_POLLING // Poll buttons at ~1kHz on 8-bit AVR. Set to 'false' for slow polling on 32-bit. + // @section safety /** @@ -2000,7 +2358,7 @@ //#define WATCHDOG_RESET_MANUAL #endif -// @section lcd +// @section baby-stepping /** * Babystepping enables movement of the axes by tiny increments without changing @@ -2011,20 +2369,20 @@ */ //#define BABYSTEPPING #if ENABLED(BABYSTEPPING) - //#define INTEGRATED_BABYSTEPPING // EXPERIMENTAL integration of babystepping into the Stepper ISR + //#define EP_BABYSTEPPING // M293/M294 babystepping with EMERGENCY_PARSER support //#define BABYSTEP_WITHOUT_HOMING - //#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement). + //#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement) //#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA! - #define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way + //#define BABYSTEP_INVERT_Z // Enable if Z babysteps should go the other way //#define BABYSTEP_MILLIMETER_UNITS // Specify BABYSTEP_MULTIPLICATOR_(XY|Z) in mm instead of micro-steps #define BABYSTEP_MULTIPLICATOR_Z 1 // (steps or mm) Steps or millimeter distance for each Z babystep #define BABYSTEP_MULTIPLICATOR_XY 1 // (steps or mm) Steps or millimeter distance for each XY babystep //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping. #if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING) - #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds. + #define DOUBLECLICK_MAX_INTERVAL 1250 // (ms) Maximum interval between clicks. // Note: Extra time may be added to mitigate controller latency. - //#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle. + //#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on double-click when printer is idle. #if ENABLED(MOVE_Z_WHEN_IDLE) #define MOVE_Z_IDLE_MULTIPLICATOR 1 // Multiply 1mm by this factor for the move step size. #endif @@ -2035,7 +2393,7 @@ //#define BABYSTEP_ZPROBE_OFFSET // Combine M851 Z and Babystepping #if ENABLED(BABYSTEP_ZPROBE_OFFSET) //#define BABYSTEP_HOTEND_Z_OFFSET // For multiple hotends, babystep relative Z offsets - //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor + //#define BABYSTEP_GFX_OVERLAY // Enable graphical overlay on Z-offset editor #endif #endif @@ -2057,12 +2415,49 @@ * See https://marlinfw.org/docs/features/lin_advance.html for full instructions. */ //#define LIN_ADVANCE + +#if ANY(LIN_ADVANCE, FT_MOTION) + #if ENABLED(DISTINCT_E_FACTORS) + #define ADVANCE_K { 0.22 } // (mm) Compression length per 1mm/s extruder speed, per extruder. Override with 'M900 T K'. + #else + #define ADVANCE_K 0.22 // (mm) Compression length for all extruders. Override with 'M900 K'. + #endif + //#define ADVANCE_K_EXTRA // Add a second linear advance constant, configurable with 'M900 L'. +#endif + #if ENABLED(LIN_ADVANCE) - //#define EXTRA_LIN_ADVANCE_K // Enable for second linear advance constants - #define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed - //#define LA_DEBUG // If enabled, this will generate debug information output over USB. - //#define EXPERIMENTAL_SCURVE // Enable this option to permit S-Curve Acceleration - //#define ALLOW_LOW_EJERK // Allow a DEFAULT_EJERK value of <10. Recommended for direct drive hotends. + //#define LA_DEBUG // Print debug information to serial during operation. Disable for production use. + //#define EXPERIMENTAL_I2S_LA // Allow I2S_STEPPER_STREAM to be used with LA. Performance degrades as the LA step rate reaches ~20kHz. + + //#define SMOOTH_LIN_ADVANCE // Remove limits on acceleration by gradual increase of nozzle pressure + #if ENABLED(SMOOTH_LIN_ADVANCE) + /** + * ADVANCE_TAU is also the time ahead that the smoother needs to look + * into the planner, so the planner needs to have enough blocks loaded. + * For k=0.04 at 10k acceleration and an "Orbiter 2" extruder it can be as low as 0.0075. + * Adjust by lowering the value until you observe the extruder skipping, then raise slightly. + * Higher k and higher XY acceleration may require larger ADVANCE_TAU to avoid skipping steps. + */ + #if ENABLED(DISTINCT_E_FACTORS) + #define ADVANCE_TAU { 0.02 } // (s) Smoothing time to reduce extruder acceleration, per extruder + #else + #define ADVANCE_TAU 0.02 // (s) Smoothing time to reduce extruder acceleration + #endif + #define SMOOTH_LIN_ADV_HZ 1000 // (Hz) How often to update extruder speed + #define INPUT_SHAPING_E_SYNC // Synchronize the extruder-shaped XY axes (to increase precision) + #endif +#endif + +/** + * Nonlinear Extrusion Control + * + * Control extrusion rate based on instantaneous extruder velocity. Can be used to correct for + * underextrusion at high extruder speeds that are otherwise well-behaved (i.e., not skipping). + * For better results also enable ADAPTIVE_STEP_SMOOTHING. + */ +//#define NONLINEAR_EXTRUSION +#if ENABLED(NONLINEAR_EXTRUSION) + //#define NONLINEAR_EXTRUSION_DEFAULT_ON // Enable if NLE should be ON by default #endif // @section leveling @@ -2086,13 +2481,10 @@ * Points to probe for all 3-point Leveling procedures. * Override if the automatically selected points are inadequate. */ -#if EITHER(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_UBL) - //#define PROBE_PT_1_X 15 - //#define PROBE_PT_1_Y 180 - //#define PROBE_PT_2_X 15 - //#define PROBE_PT_2_Y 20 - //#define PROBE_PT_3_X 170 - //#define PROBE_PT_3_Y 20 +#if NEEDS_THREE_PROBE_POINTS + //#define PROBE_PT_1 { 15, 180 } // (mm) { x, y } + //#define PROBE_PT_2 { 15, 20 } + //#define PROBE_PT_3 { 170, 20 } #endif /** @@ -2121,7 +2513,7 @@ //#define PROBING_MARGIN_BACK PROBING_MARGIN #endif -#if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) +#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) // Override the mesh area if the automatic (max) area is too large //#define MESH_MIN_X MESH_INSET //#define MESH_MIN_Y MESH_INSET @@ -2129,7 +2521,7 @@ //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET) #endif -#if BOTH(AUTO_BED_LEVELING_UBL, EEPROM_SETTINGS) +#if ALL(AUTO_BED_LEVELING_UBL, EEPROM_SETTINGS) //#define OPTIMIZED_MESH_STORAGE // Store mesh with less precision to save EEPROM space #endif @@ -2151,6 +2543,8 @@ #endif +// @section probes + /** * Thermal Probe Compensation * @@ -2199,7 +2593,7 @@ #endif // G76 options - #if BOTH(PTC_PROBE, PTC_BED) + #if ALL(PTC_PROBE, PTC_BED) // Park position to wait for probe cooldown #define PTC_PARK_POS { 0, 0, 100 } @@ -2213,17 +2607,19 @@ // Height above Z=0.0 to raise the nozzle. Lowering this can help the probe to heat faster. // Note: The Z=0.0 offset is determined by the probe Z offset (e.g., as set with M851 Z). - #define PTC_PROBE_HEATING_OFFSET 0.5 + #define PTC_PROBE_HEATING_OFFSET 0.5 // (mm) #endif #endif // PTC_PROBE || PTC_BED || PTC_HOTEND -// @section extras +// @section gcode // // G60/G61 Position Save and Return // //#define SAVED_POSITIONS 1 // Each saved position slot costs 12 bytes +// @section motion + // // G2/G3 Arc Support // @@ -2241,7 +2637,7 @@ // G5 Bézier Curve Support with XYZE destination and IJPQ offsets //#define BEZIER_CURVE_SUPPORT // Requires ~2666 bytes -#if EITHER(ARC_SUPPORT, BEZIER_CURVE_SUPPORT) +#if ANY(ARC_SUPPORT, BEZIER_CURVE_SUPPORT) //#define CNC_WORKSPACE_PLANES // Allow G2/G3/G5 to operate in XY, ZX, or YZ planes #endif @@ -2255,6 +2651,8 @@ */ //#define DIRECT_STEPPING +// @section calibrate + /** * G38 Probe Target * @@ -2268,6 +2666,8 @@ #define G38_MINIMUM_MOVE 0.0275 // (mm) Minimum distance that will produce a move. #endif +// @section motion + // Moves (or segments) with fewer steps than this will be joined with the next move #define MIN_STEPS_PER_SEGMENT 6 @@ -2288,27 +2688,28 @@ //#define MINIMUM_STEPPER_PRE_DIR_DELAY 650 /** - * Minimum stepper driver pulse width (in µs) - * 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers - * 0 : Minimum 500ns for LV8729, adjusted in stepper.h - * 1 : Minimum for A4988 and A5984 stepper drivers - * 2 : Minimum for DRV8825 stepper drivers - * 3 : Minimum for TB6600 stepper drivers - * 30 : Minimum for TB6560 stepper drivers + * Minimum stepper driver pulse width (in ns) + * If undefined, these defaults (from Conditionals-4-adv.h) apply: + * 100 : Minimum for TMC2xxx stepper drivers + * 500 : Minimum for LV8729 + * 1000 : Minimum for A4988 and A5984 stepper drivers + * 2000 : Minimum for DRV8825 stepper drivers + * 3000 : Minimum for TB6600 stepper drivers + * 30000 : Minimum for TB6560 stepper drivers * * Override the default value based on the driver type set in Configuration.h. */ -//#define MINIMUM_STEPPER_PULSE 2 +//#define MINIMUM_STEPPER_PULSE_NS 2000 /** * Maximum stepping rate (in Hz) the stepper driver allows - * If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE) + * If undefined, these defaults (from Conditionals-4-adv.h) apply: * 5000000 : Maximum for TMC2xxx stepper drivers * 1000000 : Maximum for LV8729 stepper driver - * 500000 : Maximum for A4988 stepper driver - * 250000 : Maximum for DRV8825 stepper driver - * 150000 : Maximum for TB6600 stepper driver - * 15000 : Maximum for TB6560 stepper driver + * 500000 : Maximum for A4988 stepper driver + * 250000 : Maximum for DRV8825 stepper driver + * 150000 : Maximum for TB6600 stepper driver + * 15000 : Maximum for TB6560 stepper driver * * Override the default value based on the driver type set in Configuration.h. */ @@ -2323,13 +2724,12 @@ //================================= Buffers ================================= //=========================================================================== -// @section motion +// @section gcode // The number of linear moves that can be in the planner at once. -// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32) -#if BOTH(SDSUPPORT, DIRECT_STEPPING) +#if ALL(HAS_MEDIA, DIRECT_STEPPING) #define BLOCK_BUFFER_SIZE 8 -#elif ENABLED(SDSUPPORT) +#elif HAS_MEDIA #define BLOCK_BUFFER_SIZE 16 #else #define BLOCK_BUFFER_SIZE 16 @@ -2341,19 +2741,23 @@ #define MAX_CMD_SIZE 96 #define BUFSIZE 4 -// Transmission to Host Buffer Size -// 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. -// Other output doesn't need to be that speedy. -// :[0, 2, 4, 8, 16, 32, 64, 128, 256] +/** + * Host Transmit Buffer Size + * - Costs 386 bytes of flash and TX_BUFFER_SIZE+3 bytes of SRAM (if not 0). + * - 4 bytes required to buffer a simple "ok". + * - 32 bytes for ADVANCED_OK (M105). + * - 128 bytes for the optimal speed of 'debug-echo:' + * - Other output doesn't need to be that speedy. + * :[0, 2, 4, 8, 16, 32, 64, 128, 256] + */ #define TX_BUFFER_SIZE 0 -// Host Receive Buffer Size -// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough. -// To use flow control, set this buffer size to at least 1024 bytes. -// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048] +/** + * Host Receive Buffer Size + * Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough. + * To use flow control, set this buffer size to at least 1024 bytes. + * :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048] + */ //#define RX_BUFFER_SIZE 1024 #if RX_BUFFER_SIZE >= 1024 @@ -2362,7 +2766,7 @@ //#define SERIAL_XON_XOFF #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA // Enable this option to collect and display the maximum // RX queue usage after transferring a file to SD. //#define SERIAL_STATS_MAX_RX_QUEUED @@ -2408,11 +2812,13 @@ //#define FULL_REPORT_TO_HOST_FEATURE // Auto-report the machine status like Grbl CNC #endif -// Bad Serial-connections can miss a received command by sending an 'ok' -// Therefore some clients abort after 30 seconds in a timeout. -// Some other clients start sending commands while receiving a 'wait'. -// This "wait" is only sent when the buffer is empty. 1 second is a good value here. -//#define NO_TIMEOUTS 1000 // Milliseconds +/** + * Bad Serial-connections can miss a received command by sending an 'ok' + * Therefore some clients abort after 30 seconds in a timeout. + * Some other clients start sending commands while receiving a 'wait'. + * This "wait" is only sent when the buffer is empty. 1 second is a good value here. + */ +//#define NO_TIMEOUTS 1000 // (ms) // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK @@ -2424,9 +2830,18 @@ // For serial echo, the number of digits after the decimal point //#define SERIAL_FLOAT_PRECISION 4 +/** + * This feature is EXPERIMENTAL so use with caution and test thoroughly. + * Enable this option to receive data on the serial ports via the onboard DMA + * controller for more stable and reliable high-speed serial communication. + * Support is currently limited to some STM32 MCUs and all HC32 MCUs. + * Note: This has no effect on emulated USB serial ports. + */ +//#define SERIAL_DMA + /** * Set the number of proportional font spaces required to fill up a typical character space. - * This can help to better align the output of commands like `G29 O` Mesh Output. + * This can help to better align the output of commands like 'G29 O' Mesh Output. * * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. * Otherwise, adjust according to your client and font. @@ -2444,6 +2859,8 @@ */ //#define EXTRA_FAN_SPEED +// @section firmware retraction + /** * Firmware-based and LCD-controlled retract * @@ -2478,6 +2895,8 @@ #endif #endif +// @section tool change + /** * Universal tool change settings. * Applies to all types of extruders except where explicitly noted. @@ -2495,9 +2914,17 @@ * Extra G-code to run while executing tool-change commands. Can be used to use an additional * stepper motor (e.g., I axis in Configuration.h) to drive the tool-changer. */ - //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 - //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 - //#define EVENT_GCODE_TOOLCHANGE_ALWAYS_RUN // Always execute above G-code sequences. Use with caution! + //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 + //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 + //#define EVENT_GCODE_TOOLCHANGE_ALWAYS_RUN // Always execute above G-code sequences. Use with caution! + + /** + * Consider coordinates for EVENT_GCODE_TOOLCHANGE_Tx as relative to T0 + * so that moves in the specified axes are the same for all tools. + */ + //#define TC_GCODE_USE_GLOBAL_X // Use X position relative to Tool 0 + //#define TC_GCODE_USE_GLOBAL_Y // Use Y position relative to Tool 0 + //#define TC_GCODE_USE_GLOBAL_Z // Use Z position relative to Tool 0 /** * Tool Sensors detect when tools have been picked up or dropped. @@ -2520,7 +2947,7 @@ // Longer prime to clean out a SINGLENOZZLE #define TOOLCHANGE_FS_EXTRA_PRIME 0 // (mm) Extra priming length #define TOOLCHANGE_FS_PRIME_SPEED (4.6*60) // (mm/min) Extra priming feedrate - #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm) Retract before cooling for less stringing, better wipe, etc. + #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm) Cutting retraction out of park, for less stringing, better wipe, etc. Adjust with LCD or M217 G. // Cool after prime to reduce stringing #define TOOLCHANGE_FS_FAN -1 // Fan index or -1 to skip @@ -2550,7 +2977,21 @@ * - Switch to a different nozzle on an extruder jam */ #define TOOLCHANGE_MIGRATION_FEATURE + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + // Override toolchange settings + // By default tool migration uses regular toolchange settings. + // With a prime tower, tool-change swapping/priming occur inside the bed. + // When migrating to a new unprimed tool you can set override values below. + //#define MIGRATION_ZRAISE 0 // (mm) + // Longer prime to clean out + //#define MIGRATION_FS_EXTRA_PRIME 0 // (mm) Extra priming length + //#define MIGRATION_FS_WIPE_RETRACT 0 // (mm) Retract before cooling for less stringing, better wipe, etc. + + // Cool after prime to reduce stringing + //#define MIGRATION_FS_FAN_SPEED 255 // 0-255 + //#define MIGRATION_FS_FAN_TIME 0 // (seconds) + #endif #endif /** @@ -2563,6 +3004,9 @@ #define TOOLCHANGE_PARK_XY_FEEDRATE 6000 // (mm/min) //#define TOOLCHANGE_PARK_X_ONLY // X axis only move //#define TOOLCHANGE_PARK_Y_ONLY // Y axis only move + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + //#define TOOLCHANGE_MIGRATION_DO_PARK // Force park (or no-park) on migration + #endif #endif #endif // HAS_MULTI_EXTRUDER @@ -2624,181 +3068,55 @@ //#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu. //#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302) + #define CONFIGURE_FILAMENT_CHANGE // Add M603 G-code and menu items. Requires ~1.3K bytes of flash. #endif -/** - * TMC26X Stepper Driver options - * - * The TMC26XStepper library is required for this stepper driver. - * https://github.com/trinamic/TMC26XStepper - * @section tmc/tmc26x - */ -#if HAS_DRIVER(TMC26X) - - #if AXIS_DRIVER_TYPE_X(TMC26X) - #define X_MAX_CURRENT 1000 // (mA) - #define X_SENSE_RESISTOR 91 // (mOhms) - #define X_MICROSTEPS 16 // Number of microsteps - #endif - - #if AXIS_DRIVER_TYPE_X2(TMC26X) - #define X2_MAX_CURRENT 1000 - #define X2_SENSE_RESISTOR 91 - #define X2_MICROSTEPS X_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_Y(TMC26X) - #define Y_MAX_CURRENT 1000 - #define Y_SENSE_RESISTOR 91 - #define Y_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_Y2(TMC26X) - #define Y2_MAX_CURRENT 1000 - #define Y2_SENSE_RESISTOR 91 - #define Y2_MICROSTEPS Y_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_Z(TMC26X) - #define Z_MAX_CURRENT 1000 - #define Z_SENSE_RESISTOR 91 - #define Z_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_Z2(TMC26X) - #define Z2_MAX_CURRENT 1000 - #define Z2_SENSE_RESISTOR 91 - #define Z2_MICROSTEPS Z_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_Z3(TMC26X) - #define Z3_MAX_CURRENT 1000 - #define Z3_SENSE_RESISTOR 91 - #define Z3_MICROSTEPS Z_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_Z4(TMC26X) - #define Z4_MAX_CURRENT 1000 - #define Z4_SENSE_RESISTOR 91 - #define Z4_MICROSTEPS Z_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_I(TMC26X) - #define I_MAX_CURRENT 1000 - #define I_SENSE_RESISTOR 91 - #define I_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_J(TMC26X) - #define J_MAX_CURRENT 1000 - #define J_SENSE_RESISTOR 91 - #define J_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_K(TMC26X) - #define K_MAX_CURRENT 1000 - #define K_SENSE_RESISTOR 91 - #define K_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_U(TMC26X) - #define U_MAX_CURRENT 1000 - #define U_SENSE_RESISTOR 91 - #define U_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_V(TMC26X) - #define V_MAX_CURRENT 1000 - #define V_SENSE_RESISTOR 91 - #define V_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_W(TMC26X) - #define W_MAX_CURRENT 1000 - #define W_SENSE_RESISTOR 91 - #define W_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_E0(TMC26X) - #define E0_MAX_CURRENT 1000 - #define E0_SENSE_RESISTOR 91 - #define E0_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_E1(TMC26X) - #define E1_MAX_CURRENT 1000 - #define E1_SENSE_RESISTOR 91 - #define E1_MICROSTEPS E0_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_E2(TMC26X) - #define E2_MAX_CURRENT 1000 - #define E2_SENSE_RESISTOR 91 - #define E2_MICROSTEPS E0_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_E3(TMC26X) - #define E3_MAX_CURRENT 1000 - #define E3_SENSE_RESISTOR 91 - #define E3_MICROSTEPS E0_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_E4(TMC26X) - #define E4_MAX_CURRENT 1000 - #define E4_SENSE_RESISTOR 91 - #define E4_MICROSTEPS E0_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_E5(TMC26X) - #define E5_MAX_CURRENT 1000 - #define E5_SENSE_RESISTOR 91 - #define E5_MICROSTEPS E0_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_E6(TMC26X) - #define E6_MAX_CURRENT 1000 - #define E6_SENSE_RESISTOR 91 - #define E6_MICROSTEPS E0_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_E7(TMC26X) - #define E7_MAX_CURRENT 1000 - #define E7_SENSE_RESISTOR 91 - #define E7_MICROSTEPS E0_MICROSTEPS - #endif - -#endif // TMC26X +// @section tmc_smart /** - * To use TMC2130, TMC2160, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode - * connect your SPI pins to the hardware SPI interface on your board and define - * the required CS pins in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 - * pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.). - * You may also use software SPI if you wish to use general purpose IO pins. + * Trinamic Smart Drivers * - * To use TMC2208 stepper UART-configurable stepper drivers connect #_SERIAL_TX_PIN - * to the driver side PDN_UART pin with a 1K resistor. - * To use the reading capabilities, also connect #_SERIAL_RX_PIN to PDN_UART without - * a resistor. - * The drivers can also be used with hardware serial. + * To use TMC2130, TMC2160, TMC2240, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode: + * - Connect your SPI pins to the Hardware SPI interface on the board. + * Some boards have simple jumper connections! See your board's documentation. + * - Define the required Stepper CS pins in your `pins_MYBOARD.h` file. + * (See the RAMPS pins, for example.) + * - You can also use Software SPI with GPIO pins instead of Hardware SPI. + * + * To use TMC220x stepper drivers with Serial UART: + * - Connect PDN_UART to the #_SERIAL_TX_PIN through a 1K resistor. + * For reading capabilities also connect PDN_UART to #_SERIAL_RX_PIN with no resistor. + * Some boards have simple jumper connections! See your board's documentation. + * - These drivers can also be used with Hardware Serial. + * + * The TMCStepper library is required for other TMC stepper drivers. + * https://github.com/teemuatlut/TMCStepper * - * TMCStepper library is required to use TMC stepper drivers. - * https://github.com/teemuatlut/TMCStepper * @section tmc/config */ #if HAS_TRINAMIC_CONFIG #define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current + //#define EDITABLE_HOMING_CURRENT // Add a G-code and menu to modify the Homing Current + /** * Interpolate microsteps to 256 * Override for each driver with _INTERPOLATE settings below */ #define INTERPOLATE true - #if AXIS_IS_TMC(X) + #if HAS_DRIVER(TMC2240) + #define TMC2240_RREF 12000 // (Ω) 12000 .. 60000. (FLY TMC2240 = 12300) + // Max Current. Lower for more internal resolution. Raise to run cooler. + #define TMC2240_CURRENT_RANGE 1 // :{ 0:'RMS=690mA PEAK=1A', 1:'RMS=1410mA PEAK=2A', 2:'RMS=2120mA PEAK=3A', 3:'RMS=2110mA PEAK=3A' } + // Slope Control: Lower is more silent. Higher runs cooler. + #define TMC2240_SLOPE_CONTROL 0 // :{ 0:'100V/µs', 1:'200V/µs', 2:'400V/µs', 3:'800V/µs' } + #endif + + #if AXIS_IS_TMC_CONFIG(X) #define X_CURRENT 800 // (mA) RMS current. Multiply by 1.414 for peak current. - #define X_CURRENT_HOME X_CURRENT // (mA) RMS current for sensorless homing + #define X_CURRENT_HOME X_CURRENT // (mA) RMS current for homing. (Typically lower than *_CURRENT.) #define X_MICROSTEPS 16 // 0..256 #define X_RSENSE 0.11 #define X_CHAIN_POS -1 // -1..0: Not chained. 1: MCU MOSI connected. 2: Next in chain, ... @@ -2806,17 +3124,17 @@ //#define X_HOLD_MULTIPLIER 0.5 // Enable to override 'HOLD_MULTIPLIER' for the X axis #endif - #if AXIS_IS_TMC(X2) - #define X2_CURRENT 800 - #define X2_CURRENT_HOME X2_CURRENT - #define X2_MICROSTEPS X_MICROSTEPS - #define X2_RSENSE 0.11 + #if AXIS_IS_TMC_CONFIG(X2) + #define X2_CURRENT X_CURRENT + #define X2_CURRENT_HOME X_CURRENT_HOME + #define X2_MICROSTEPS X_MICROSTEPS + #define X2_RSENSE X_RSENSE #define X2_CHAIN_POS -1 //#define X2_INTERPOLATE true //#define X2_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(Y) + #if AXIS_IS_TMC_CONFIG(Y) #define Y_CURRENT 800 #define Y_CURRENT_HOME Y_CURRENT #define Y_MICROSTEPS 16 @@ -2826,17 +3144,17 @@ //#define Y_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(Y2) - #define Y2_CURRENT 800 - #define Y2_CURRENT_HOME Y2_CURRENT - #define Y2_MICROSTEPS Y_MICROSTEPS - #define Y2_RSENSE 0.11 + #if AXIS_IS_TMC_CONFIG(Y2) + #define Y2_CURRENT Y_CURRENT + #define Y2_CURRENT_HOME Y_CURRENT_HOME + #define Y2_MICROSTEPS Y_MICROSTEPS + #define Y2_RSENSE Y_RSENSE #define Y2_CHAIN_POS -1 //#define Y2_INTERPOLATE true //#define Y2_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(Z) + #if AXIS_IS_TMC_CONFIG(Z) #define Z_CURRENT 800 #define Z_CURRENT_HOME Z_CURRENT #define Z_MICROSTEPS 16 @@ -2846,37 +3164,37 @@ //#define Z_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(Z2) - #define Z2_CURRENT 800 - #define Z2_CURRENT_HOME Z2_CURRENT - #define Z2_MICROSTEPS Z_MICROSTEPS - #define Z2_RSENSE 0.11 + #if AXIS_IS_TMC_CONFIG(Z2) + #define Z2_CURRENT Z_CURRENT + #define Z2_CURRENT_HOME Z_CURRENT_HOME + #define Z2_MICROSTEPS Z_MICROSTEPS + #define Z2_RSENSE Z_RSENSE #define Z2_CHAIN_POS -1 //#define Z2_INTERPOLATE true //#define Z2_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(Z3) - #define Z3_CURRENT 800 - #define Z3_CURRENT_HOME Z3_CURRENT - #define Z3_MICROSTEPS Z_MICROSTEPS - #define Z3_RSENSE 0.11 + #if AXIS_IS_TMC_CONFIG(Z3) + #define Z3_CURRENT Z_CURRENT + #define Z3_CURRENT_HOME Z_CURRENT_HOME + #define Z3_MICROSTEPS Z_MICROSTEPS + #define Z3_RSENSE Z_RSENSE #define Z3_CHAIN_POS -1 //#define Z3_INTERPOLATE true //#define Z3_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(Z4) - #define Z4_CURRENT 800 - #define Z4_CURRENT_HOME Z4_CURRENT - #define Z4_MICROSTEPS Z_MICROSTEPS - #define Z4_RSENSE 0.11 + #if AXIS_IS_TMC_CONFIG(Z4) + #define Z4_CURRENT Z_CURRENT + #define Z4_CURRENT_HOME Z_CURRENT_HOME + #define Z4_MICROSTEPS Z_MICROSTEPS + #define Z4_RSENSE Z_RSENSE #define Z4_CHAIN_POS -1 //#define Z4_INTERPOLATE true //#define Z4_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(I) + #if AXIS_IS_TMC_CONFIG(I) #define I_CURRENT 800 #define I_CURRENT_HOME I_CURRENT #define I_MICROSTEPS 16 @@ -2886,7 +3204,7 @@ //#define I_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(J) + #if AXIS_IS_TMC_CONFIG(J) #define J_CURRENT 800 #define J_CURRENT_HOME J_CURRENT #define J_MICROSTEPS 16 @@ -2896,7 +3214,7 @@ //#define J_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(K) + #if AXIS_IS_TMC_CONFIG(K) #define K_CURRENT 800 #define K_CURRENT_HOME K_CURRENT #define K_MICROSTEPS 16 @@ -2906,7 +3224,7 @@ //#define K_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(U) + #if AXIS_IS_TMC_CONFIG(U) #define U_CURRENT 800 #define U_CURRENT_HOME U_CURRENT #define U_MICROSTEPS 8 @@ -2916,7 +3234,7 @@ //#define U_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(V) + #if AXIS_IS_TMC_CONFIG(V) #define V_CURRENT 800 #define V_CURRENT_HOME V_CURRENT #define V_MICROSTEPS 8 @@ -2926,7 +3244,7 @@ //#define V_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(W) + #if AXIS_IS_TMC_CONFIG(W) #define W_CURRENT 800 #define W_CURRENT_HOME W_CURRENT #define W_MICROSTEPS 8 @@ -2936,7 +3254,7 @@ //#define W_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(E0) + #if AXIS_IS_TMC_CONFIG(E0) #define E0_CURRENT 800 #define E0_MICROSTEPS 16 #define E0_RSENSE 0.11 @@ -2945,107 +3263,114 @@ //#define E0_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(E1) - #define E1_CURRENT 800 + #if AXIS_IS_TMC_CONFIG(E1) + #define E1_CURRENT E0_CURRENT #define E1_MICROSTEPS E0_MICROSTEPS - #define E1_RSENSE 0.11 + #define E1_RSENSE E0_RSENSE #define E1_CHAIN_POS -1 //#define E1_INTERPOLATE true //#define E1_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(E2) - #define E2_CURRENT 800 + #if AXIS_IS_TMC_CONFIG(E2) + #define E2_CURRENT E0_CURRENT #define E2_MICROSTEPS E0_MICROSTEPS - #define E2_RSENSE 0.11 + #define E2_RSENSE E0_RSENSE #define E2_CHAIN_POS -1 //#define E2_INTERPOLATE true //#define E2_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(E3) - #define E3_CURRENT 800 + #if AXIS_IS_TMC_CONFIG(E3) + #define E3_CURRENT E0_CURRENT #define E3_MICROSTEPS E0_MICROSTEPS - #define E3_RSENSE 0.11 + #define E3_RSENSE E0_RSENSE #define E3_CHAIN_POS -1 //#define E3_INTERPOLATE true //#define E3_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(E4) - #define E4_CURRENT 800 + #if AXIS_IS_TMC_CONFIG(E4) + #define E4_CURRENT E0_CURRENT #define E4_MICROSTEPS E0_MICROSTEPS - #define E4_RSENSE 0.11 + #define E4_RSENSE E0_RSENSE #define E4_CHAIN_POS -1 //#define E4_INTERPOLATE true //#define E4_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(E5) - #define E5_CURRENT 800 + #if AXIS_IS_TMC_CONFIG(E5) + #define E5_CURRENT E0_CURRENT #define E5_MICROSTEPS E0_MICROSTEPS - #define E5_RSENSE 0.11 + #define E5_RSENSE E0_RSENSE #define E5_CHAIN_POS -1 //#define E5_INTERPOLATE true //#define E5_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(E6) - #define E6_CURRENT 800 + #if AXIS_IS_TMC_CONFIG(E6) + #define E6_CURRENT E0_CURRENT #define E6_MICROSTEPS E0_MICROSTEPS - #define E6_RSENSE 0.11 + #define E6_RSENSE E0_RSENSE #define E6_CHAIN_POS -1 //#define E6_INTERPOLATE true //#define E6_HOLD_MULTIPLIER 0.5 #endif - #if AXIS_IS_TMC(E7) - #define E7_CURRENT 800 + #if AXIS_IS_TMC_CONFIG(E7) + #define E7_CURRENT E0_CURRENT #define E7_MICROSTEPS E0_MICROSTEPS - #define E7_RSENSE 0.11 + #define E7_RSENSE E0_RSENSE #define E7_CHAIN_POS -1 //#define E7_INTERPOLATE true //#define E7_HOLD_MULTIPLIER 0.5 #endif + /** + * Use the homing current for all probing. (e.g., Current may be reduced to the + * point where a collision makes the motor skip instead of damaging the bed, + * though this is unlikely to save delicate probes from being damaged. + */ + //#define PROBING_USE_CURRENT_HOME + // @section tmc/spi /** - * Override default SPI pins for TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160 drivers here. + * Override default SPI pins for TMC2130, TMC2160, TMC2240, TMC2660, TMC5130 and TMC5160 drivers here. * The default pins can be found in your board's pins file. */ - //#define X_CS_PIN -1 - //#define Y_CS_PIN -1 - //#define Z_CS_PIN -1 - //#define X2_CS_PIN -1 - //#define Y2_CS_PIN -1 - //#define Z2_CS_PIN -1 - //#define Z3_CS_PIN -1 - //#define Z4_CS_PIN -1 - //#define I_CS_PIN -1 - //#define J_CS_PIN -1 - //#define K_CS_PIN -1 - //#define U_CS_PIN -1 - //#define V_CS_PIN -1 - //#define W_CS_PIN -1 - //#define E0_CS_PIN -1 - //#define E1_CS_PIN -1 - //#define E2_CS_PIN -1 - //#define E3_CS_PIN -1 - //#define E4_CS_PIN -1 - //#define E5_CS_PIN -1 - //#define E6_CS_PIN -1 - //#define E7_CS_PIN -1 + //#define X_CS_PIN -1 + //#define Y_CS_PIN -1 + //#define Z_CS_PIN -1 + //#define X2_CS_PIN -1 + //#define Y2_CS_PIN -1 + //#define Z2_CS_PIN -1 + //#define Z3_CS_PIN -1 + //#define Z4_CS_PIN -1 + //#define I_CS_PIN -1 + //#define J_CS_PIN -1 + //#define K_CS_PIN -1 + //#define U_CS_PIN -1 + //#define V_CS_PIN -1 + //#define W_CS_PIN -1 + //#define E0_CS_PIN -1 + //#define E1_CS_PIN -1 + //#define E2_CS_PIN -1 + //#define E3_CS_PIN -1 + //#define E4_CS_PIN -1 + //#define E5_CS_PIN -1 + //#define E6_CS_PIN -1 + //#define E7_CS_PIN -1 /** - * Software option for SPI driven drivers (TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160). + * Software option for SPI driven drivers (TMC2130, TMC2160, TMC2240, TMC2660, TMC5130 and TMC5160). * The default SW SPI pins are defined the respective pins files, * but you can override or define them here. */ //#define TMC_USE_SW_SPI - //#define TMC_SW_MOSI -1 - //#define TMC_SW_MISO -1 - //#define TMC_SW_SCK -1 + //#define TMC_SPI_MOSI -1 + //#define TMC_SPI_MISO -1 + //#define TMC_SPI_SCK -1 // @section tmc/serial @@ -3097,19 +3422,21 @@ // @section tmc/stealthchop /** - * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only + * TMC2130, TMC2160, TMC2208, TMC2209, TMC2240, TMC5130 and TMC5160 only * Use Trinamic's ultra quiet stepping mode. * When disabled, Marlin will use spreadCycle stepping mode. */ - #define STEALTHCHOP_XY - #define STEALTHCHOP_Z - #define STEALTHCHOP_I - #define STEALTHCHOP_J - #define STEALTHCHOP_K - #define STEALTHCHOP_U - #define STEALTHCHOP_V - #define STEALTHCHOP_W - #define STEALTHCHOP_E + #if HAS_STEALTHCHOP + #define STEALTHCHOP_XY + #define STEALTHCHOP_Z + #define STEALTHCHOP_I + #define STEALTHCHOP_J + #define STEALTHCHOP_K + #define STEALTHCHOP_U + #define STEALTHCHOP_V + #define STEALTHCHOP_W + #define STEALTHCHOP_E + #endif /** * Optimize spreadCycle chopper parameters by using predefined parameter sets @@ -3174,7 +3501,7 @@ // @section tmc/hybrid /** - * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only + * TMC2130, TMC2160, TMC2208, TMC2209, TMC2240, TMC5130 and TMC5160 only * The driver will switch to spreadCycle when stepper speed is over HYBRID_THRESHOLD. * This mode allows for faster movements at the expense of higher noise levels. * STEALTHCHOP_(XY|Z|E) must be enabled to use HYBRID_THRESHOLD. @@ -3208,20 +3535,20 @@ /** * Use StallGuard to home / probe X, Y, Z. * - * TMC2130, TMC2160, TMC2209, TMC2660, TMC5130, and TMC5160 only + * TMC2130, TMC2160, TMC2209, TMC2240, TMC2660, TMC5130, and TMC5160 only * Connect the stepper driver's DIAG1 pin to the X/Y endstop pin. * X, Y, and Z homing will always be done in spreadCycle mode. * * X/Y/Z_STALL_SENSITIVITY is the default stall threshold. * Use M914 X Y Z to set the stall threshold at runtime: * - * Sensitivity TMC2209 Others - * HIGHEST 255 -64 (Too sensitive => False positive) - * LOWEST 0 63 (Too insensitive => No trigger) + * Sensitivity TMC2209 Others + * HIGHEST 255 -64 (Too sensitive => False positive) + * LOWEST 0 63 (Too insensitive => No trigger) * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * - * SPI_ENDSTOPS *** Beta feature! *** TMC2130/TMC5160 Only *** + * SPI_ENDSTOPS *** TMC2130, TMC2240, and TMC5160 Only *** * Poll the driver through SPI to determine load when homing. * Removes the need for a wire from DIAG1 to an endstop pin. * @@ -3233,7 +3560,7 @@ */ //#define SENSORLESS_HOMING // StallGuard capable drivers only - #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + #if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) // TMC2209: 0...255. TMC2130: -64...63 #define X_STALL_SENSITIVITY 8 #define X2_STALL_SENSITIVITY X_STALL_SENSITIVITY @@ -3249,8 +3576,9 @@ //#define U_STALL_SENSITIVITY 8 //#define V_STALL_SENSITIVITY 8 //#define W_STALL_SENSITIVITY 8 - //#define SPI_ENDSTOPS // TMC2130 only + //#define SPI_ENDSTOPS // TMC2130, TMC2240, and TMC5160 //#define IMPROVE_HOMING_RELIABILITY + //#define SENSORLESS_STALLGUARD_DELAY 0 // (ms) Delay to allow drivers to settle #endif // @section tmc/config @@ -3268,10 +3596,9 @@ //#define TMC_HOME_PHASE { 896, 896, 896 } /** - * Beta feature! - * Create a 50/50 square wave step pulse optimal for stepper drivers. + * Step on both rising and falling edge signals (as with a square wave). */ - //#define SQUARE_WAVE_STEPPING + #define EDGE_STEPPING /** * Enable M122 debugging command for TMC stepper drivers. @@ -3305,9 +3632,8 @@ /** * TWI/I2C BUS * - * This feature is an EXPERIMENTAL feature so it shall not be used on production - * machines. Enabling this will allow you to send and receive I2C data from slave - * devices on the bus. + * This feature is EXPERIMENTAL but may be useful for custom I2C peripherals. + * Enable this to send and receive I2C data from slave devices on the bus. * * ; Example #1 * ; This macro send the string "Marlin" to the slave device with address 0x63 (99) @@ -3350,11 +3676,11 @@ //#define PHOTO_RETRACT_MM 6.5 // (mm) E retract/recover for the photo move (M240 R S) // Canon RC-1 or homebrew digital camera trigger - // Data from: https://www.doc-diy.net/photo/rc-1_hacked/ + // Data from: https://web.archive.org/web/20250327153953/www.doc-diy.net/photo/rc-1_hacked/ //#define PHOTOGRAPH_PIN 23 // Canon Hack Development Kit - // https://captain-slow.dk/2014/03/09/3d-printing-timelapses/ + // https://web.archive.org/web/20200920094805/captain-slow.dk/2014/03/09/3d-printing-timelapses/ //#define CHDK_PIN 4 // Optional second move with delay to trigger the camera shutter @@ -3386,7 +3712,7 @@ * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and * to set spindle speed, spindle direction, and laser power. * - * SuperPid is a router/spindle speed controller used in the CNC milling community. + * SuperPID is a router/spindle speed controller used in the CNC milling community. * Marlin can be used to turn the spindle on and off. It can also be used to set * the spindle speed from 5,000 to 30,000 RPM. * @@ -3397,7 +3723,7 @@ */ //#define SPINDLE_FEATURE //#define LASER_FEATURE -#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) +#if ANY(SPINDLE_FEATURE, LASER_FEATURE) #define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if SPINDLE_LASER_ENA_PIN is active HIGH #define SPINDLE_LASER_USE_PWM // Enable if your controller supports setting the speed/power @@ -3468,6 +3794,8 @@ #define SPEED_POWER_MIN 5000 // (RPM) #define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM #define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments) + + //#define DEFAULT_ACCELERATION_SPINDLE 1000 // (°/s/s) Default spindle acceleration (speed change with time) #endif #else @@ -3508,7 +3836,7 @@ * Feed rates are set by the F parameter of a move command e.g. G1 X0 Y10 F6000 * Laser power would be calculated by bit shifting off 8 LSB's. In binary this is div 256. * The calculation gives us ocr values from 0 to 255, values over F65535 will be set as 255 . - * More refined power control such as compesation for accell/decell will be addressed in future releases. + * More refined power control such as compensation for accel/decel will be addressed in future releases. * * M5 I clears inline mode and set power to 0, M5 sets the power output to 0 but leaves inline mode on. */ @@ -3516,8 +3844,8 @@ /** * Enable M3 commands for laser mode inline power planner syncing. * This feature enables any M3 S-value to be injected into the block buffers while in - * CUTTER_MODE_CONTINUOUS. The option allows M3 laser power to be commited without waiting - * for a planner syncronization + * CUTTER_MODE_CONTINUOUS. The option allows M3 laser power to be committed without waiting + * for a planner synchronization */ //#define LASER_POWER_SYNC @@ -3664,35 +3992,6 @@ */ //#define CNC_COORDINATE_SYSTEMS -// @section reporting - -/** - * Auto-report fan speed with M123 S - * Requires fans with tachometer pins - */ -//#define AUTO_REPORT_FANS - -/** - * Auto-report temperatures with M155 S - */ -#define AUTO_REPORT_TEMPERATURES -#if ENABLED(AUTO_REPORT_TEMPERATURES) && TEMP_SENSOR_REDUNDANT - //#define AUTO_REPORT_REDUNDANT // Include the "R" sensor in the auto-report -#endif - -/** - * Auto-report position with M154 S - */ -//#define AUTO_REPORT_POSITION - -/** - * Include capabilities in M115 output - */ -#define EXTENDED_CAPABILITIES_REPORT -#if ENABLED(EXTENDED_CAPABILITIES_REPORT) - //#define M115_GEOMETRY_REPORT -#endif - // @section security /** @@ -3728,31 +4027,70 @@ * Use 'M200 [T] L' to override and 'M502' to reset. * A non-zero value activates Volume-based Extrusion Limiting. */ - #define DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT 0.00 // (mm^3/sec) + #define DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT 0.00 // (mm^3/sec) + #define VOLUMETRIC_EXTRUDER_LIMIT_MAX 20 // (mm^3/sec) #endif #endif // @section reporting -// Extra options for the M114 "Current Position" report -//#define M114_DETAIL // Use 'M114` for details to check planner calculations +/** + * Extra options for the M114 "Current Position" report + */ +//#define M114_DETAIL // Use 'M114 D' for details to check planner calculations //#define M114_REALTIME // Real current position based on forward kinematics //#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed. +/** + * Auto-report fan speed with M123 S + * Requires fans with tachometer pins + */ +//#define AUTO_REPORT_FANS + //#define REPORT_FAN_CHANGE // Report the new fan speed when changed by M106 (and others) +/** + * Auto-report temperatures with M155 S + */ +#define AUTO_REPORT_TEMPERATURES +#if ENABLED(AUTO_REPORT_TEMPERATURES) && TEMP_SENSOR_REDUNDANT + //#define AUTO_REPORT_REDUNDANT // Include the "R" sensor in the auto-report +#endif + +/** + * Auto-report position with M154 S + */ +//#define AUTO_REPORT_POSITION +#if ENABLED(AUTO_REPORT_POSITION) + //#define AUTO_REPORT_REAL_POSITION // Auto-report the real position +#endif + +/** + * M115 - Report capabilities. Disable to save ~1150 bytes of flash. + * Some hosts (and serial TFT displays) rely on this feature. + */ +#define CAPABILITIES_REPORT +#if ENABLED(CAPABILITIES_REPORT) + // Include capabilities in M115 output + #define EXTENDED_CAPABILITIES_REPORT + #if ENABLED(EXTENDED_CAPABILITIES_REPORT) + //#define M115_GEOMETRY_REPORT + #endif +#endif + // @section gcode /** * Spend 28 bytes of SRAM to optimize the G-code parser */ #define FASTER_GCODE_PARSER - #if ENABLED(FASTER_GCODE_PARSER) //#define GCODE_QUOTED_STRINGS // Support for quoted string parameters #endif -// Support for MeatPack G-code compression (https://github.com/scottmudge/OctoPrint-MeatPack) +/** + * Support for MeatPack G-code compression (https://github.com/scottmudge/OctoPrint-MeatPack) + */ //#define MEATPACK_ON_SERIAL_PORT_1 //#define MEATPACK_ON_SERIAL_PORT_2 @@ -3761,14 +4099,23 @@ //#define REPETIER_GCODE_M360 // Add commands originally from Repetier FW /** - * Enable this option for a leaner build of Marlin that removes all - * workspace offsets, simplifying coordinate transformations, leveling, etc. - * - * - M206 and M428 are disabled. - * - G92 will revert to its behavior from Marlin 1.0. + * Enable M111 debug flags 1=ECHO, 2=INFO, 4=ERRORS (unimplemented). + * Disable to save some flash. Some hosts (Repetier Host) may rely on this feature. + */ +#define DEBUG_FLAGS_GCODE + +/** + * Enable this option for a leaner build of Marlin that removes + * workspace offsets to slightly optimize performance. + * G92 will revert to its behavior from Marlin 1.0. */ //#define NO_WORKSPACE_OFFSETS +/** + * Disable M206 and M428 if you don't need home offsets. + */ +//#define NO_HOME_OFFSETS + /** * CNC G-code options * Support CNC-style G-code dialects used by laser cutters, drawing machine cams, etc. @@ -3784,8 +4131,6 @@ //#define VARIABLE_G0_FEEDRATE // The G0 feedrate is set by F in G0 motion mode #endif -// @section gcode - /** * Startup commands * @@ -3796,13 +4141,17 @@ /** * G-code Macros * - * Add G-codes M810-M819 to define and run G-code macros. - * Macros are not saved to EEPROM. + * Add G-codes M810-M819 to define and run G-code macros + * and M820 to report the current set of macros. + * Macros are not saved to EEPROM unless enabled below. */ //#define GCODE_MACROS #if ENABLED(GCODE_MACROS) #define GCODE_MACROS_SLOTS 5 // Up to 10 may be used #define GCODE_MACROS_SLOT_SIZE 50 // Maximum length of a single macro + #if ENABLED(EEPROM_SETTINGS) + //#define GCODE_MACROS_IN_EEPROM // Include macros in EEPROM + #endif #endif /** @@ -3824,22 +4173,27 @@ #define MAIN_MENU_ITEM_1_DESC "Home & UBL Info" #define MAIN_MENU_ITEM_1_GCODE "G28\nG29 W" //#define MAIN_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action + //#define MAIN_MENU_ITEM_1_IMMEDIATE // Skip the queue and execute immediately. Rarely needed. #define MAIN_MENU_ITEM_2_DESC "Preheat for " PREHEAT_1_LABEL #define MAIN_MENU_ITEM_2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) //#define MAIN_MENU_ITEM_2_CONFIRM + //#define MAIN_MENU_ITEM_2_IMMEDIATE //#define MAIN_MENU_ITEM_3_DESC "Preheat for " PREHEAT_2_LABEL //#define MAIN_MENU_ITEM_3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) //#define MAIN_MENU_ITEM_3_CONFIRM + //#define MAIN_MENU_ITEM_3_IMMEDIATE //#define MAIN_MENU_ITEM_4_DESC "Heat Bed/Home/Level" //#define MAIN_MENU_ITEM_4_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" //#define MAIN_MENU_ITEM_4_CONFIRM + //#define MAIN_MENU_ITEM_4_IMMEDIATE //#define MAIN_MENU_ITEM_5_DESC "Home & Info" //#define MAIN_MENU_ITEM_5_GCODE "G28\nM503" //#define MAIN_MENU_ITEM_5_CONFIRM + //#define MAIN_MENU_ITEM_5_IMMEDIATE #endif // @section custom config menu @@ -3856,22 +4210,27 @@ #define CONFIG_MENU_ITEM_1_DESC "Wifi ON" #define CONFIG_MENU_ITEM_1_GCODE "M118 [ESP110] WIFI-STA pwd=12345678" //#define CONFIG_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action + //#define CONFIG_MENU_ITEM_1_IMMEDIATE // Skip the queue and execute immediately. Rarely needed. #define CONFIG_MENU_ITEM_2_DESC "Bluetooth ON" #define CONFIG_MENU_ITEM_2_GCODE "M118 [ESP110] BT pwd=12345678" //#define CONFIG_MENU_ITEM_2_CONFIRM + //#define CONFIG_MENU_ITEM_2_IMMEDIATE //#define CONFIG_MENU_ITEM_3_DESC "Radio OFF" //#define CONFIG_MENU_ITEM_3_GCODE "M118 [ESP110] OFF pwd=12345678" //#define CONFIG_MENU_ITEM_3_CONFIRM + //#define CONFIG_MENU_ITEM_3_IMMEDIATE //#define CONFIG_MENU_ITEM_4_DESC "Wifi ????" //#define CONFIG_MENU_ITEM_4_GCODE "M118 ????" //#define CONFIG_MENU_ITEM_4_CONFIRM + //#define CONFIG_MENU_ITEM_4_IMMEDIATE //#define CONFIG_MENU_ITEM_5_DESC "Wifi ????" //#define CONFIG_MENU_ITEM_5_GCODE "M118 ????" //#define CONFIG_MENU_ITEM_5_CONFIRM + //#define CONFIG_MENU_ITEM_5_IMMEDIATE #endif // @section custom buttons @@ -3888,6 +4247,7 @@ #define BUTTON1_WHEN_PRINTING false // Button allowed to trigger during printing? #define BUTTON1_GCODE "G28" #define BUTTON1_DESC "Homing" // Optional string to set the LCD status + //#define BUTTON1_IMMEDIATE // Skip the queue and execute immediately. Rarely needed. #endif //#define BUTTON2_PIN -1 @@ -3896,6 +4256,7 @@ #define BUTTON2_WHEN_PRINTING false #define BUTTON2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) #define BUTTON2_DESC "Preheat for " PREHEAT_1_LABEL + //#define BUTTON2_IMMEDIATE #endif //#define BUTTON3_PIN -1 @@ -3904,6 +4265,7 @@ #define BUTTON3_WHEN_PRINTING false #define BUTTON3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) #define BUTTON3_DESC "Preheat for " PREHEAT_2_LABEL + //#define BUTTON3_IMMEDIATE #endif #endif @@ -3951,9 +4313,9 @@ * Developed by Chris Barr at Aus3D. * * Wiki: https://wiki.aus3d.com.au/Magnetic_Encoder - * Github: https://github.com/Aus3D/MagneticEncoder + * GitHub: https://github.com/Aus3D/MagneticEncoder * - * Supplier: https://aus3d.com.au/magnetic-encoder-module + * Supplier: https://aus3d.com.au/products/magnetic-encoder-module * Alternative Supplier: https://reliabuild3d.com/ * * Reliabuild encoders have been modified to improve reliability. @@ -3976,7 +4338,7 @@ //#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper // steps per full revolution (motor steps/rev * microstepping) //#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel. - #define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction. + #define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error correction. #define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the // printer will attempt to correct the error; errors // smaller than this are ignored to minimize effects of @@ -4051,7 +4413,7 @@ /** * Mechanical Gantry Calibration - * Modern replacement for the Prusa TMC_Z_CALIBRATION. + * Modern replacement for the Průša TMC_Z_CALIBRATION. * Adds capability to work with any adjustable current drivers. * Implemented as G34 because M915 is deprecated. * @section calibrate @@ -4071,7 +4433,8 @@ /** * Instant freeze / unfreeze functionality - * Potentially useful for emergency stop that allows being resumed. + * Potentially useful for rapid stop that allows being resumed. Halts stepper movement. + * Note this does NOT pause spindles, lasers, fans, heaters or any other auxiliary device. * @section interface */ //#define FREEZE_FEATURE @@ -4106,16 +4469,19 @@ * Sample debug features * 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 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_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning + #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. + #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. + //#define MAX7219_DEBUG_MULTISTEPPING 6 // Show multi-stepping 1 to 128 on this LED matrix row. + //#define MAX7219_DEBUG_SLOWDOWN 6 // Count (mod 16) how many times SLOWDOWN has reduced print speed. + //#define MAX7219_REINIT_ON_POWERUP // Re-initialize MAX7129 when power supply turns on #endif /** @@ -4140,13 +4506,17 @@ #endif /** - * WiFi Support (Espressif ESP32 WiFi) + * Native ESP32 board with WiFi or add-on ESP32 WiFi-101 module */ -//#define WIFISUPPORT // Marlin embedded WiFi managenent +//#define WIFISUPPORT // Marlin embedded WiFi management. Not needed for simple WiFi serial port. //#define ESP3D_WIFISUPPORT // ESP3D Library WiFi management (https://github.com/luc-github/ESP3DLib) -#if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) - //#define WEBSUPPORT // Start a webserver (which may include auto-discovery) +/** + * Extras for an ESP32-based motherboard with WIFISUPPORT + * These options don't apply to add-on WiFi modules based on ESP32 WiFi101. + */ +#if ANY(WIFISUPPORT, ESP3D_WIFISUPPORT) + //#define WEBSUPPORT // Start a webserver (which may include auto-discovery) using SPIFFS //#define OTASUPPORT // Support over-the-air firmware updates //#define WIFI_CUSTOM_COMMAND // Accept feature config commands (e.g., WiFi ESP3D) from the host @@ -4181,31 +4551,37 @@ //#define E_MUX0_PIN 40 // Always Required //#define E_MUX1_PIN 42 // Needed for 3 to 8 inputs //#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs -#elif HAS_PRUSA_MMU2 - // Serial port used for communication with MMU2. - #define MMU2_SERIAL_PORT 2 - // Use hardware reset for MMU if a pin is defined for it - //#define MMU2_RST_PIN 23 +#elif HAS_PRUSA_MMU2 || HAS_PRUSA_MMU3 + // Common settings for MMU2/MMU2S/MMU3 + // Serial port used for communication with MMU2/MMU2S/MMU3. + #define MMU_SERIAL_PORT 2 + #define MMU_BAUD 115200 - // Enable if the MMU2 has 12V stepper motors (MMU2 Firmware 1.0.2 and up) - //#define MMU2_MODE_12V + //#define MMU_RST_PIN 23 // Define this pin to use Hardware Reset for MMU2/MMU2S/MMU3 - // G-code to execute when MMU2 F.I.N.D.A. probe detects filament runout - #define MMU2_FILAMENT_RUNOUT_SCRIPT "M600" + //#define MMU_MENUS // Add an LCD menu for MMU2/MMU2S/MMU3 + + //#define MMU_DEBUG // Write debug info to serial output + + // Options pertaining to MMU2 and MMU2S + #if HAS_PRUSA_MMU2 + // Enable if the MMU2 has 12V stepper motors (MMU2 Firmware 1.0.2 and up) + //#define MMU2_MODE_12V - // Add an LCD menu for MMU2 - //#define MMU2_MENUS - #if EITHER(MMU2_MENUS, HAS_PRUSA_MMU2S) // Settings for filament load / unload from the LCD menu. // This is for Průša MK3-style extruders. Customize for your hardware. #define MMU2_FILAMENTCHANGE_EJECT_FEED 80.0 + + // G-code to execute when MMU2 F.I.N.D.A. probe detects filament runout + #define MMU2_FILAMENT_RUNOUT_SCRIPT "M600" + + // MMU2 sequences use mm/min. Not compatible with MMU3, which use mm/sec. #define MMU2_LOAD_TO_NOZZLE_SEQUENCE \ - { 7.2, 1145 }, \ - { 14.4, 871 }, \ - { 36.0, 1393 }, \ - { 14.4, 871 }, \ - { 50.0, 198 } + { 4.4, 871 }, \ + { 10.0, 1393 }, \ + { 4.4, 871 }, \ + { 10.0, 198 } #define MMU2_RAMMING_SEQUENCE \ { 1.0, 1000 }, \ @@ -4219,21 +4595,37 @@ { 10.0, 700 }, \ { -10.0, 400 }, \ { -50.0, 2000 } - #endif + + #endif // HAS_PRUSA_MMU2 /** - * Using a sensor like the MMU2S - * This mode requires a MK3S extruder with a sensor at the extruder idler, like the MMU2S. - * See https://help.prusa3d.com/en/guide/3b-mk3s-mk2-5s-extruder-upgrade_41560, step 11 + * Options pertaining to MMU2S devices + * Requires the MK3S extruder with a sensor at the extruder idler, like the MMU2S. + * See https://help.prusa3d.com/guide/3b-mk3s-mk2-5s-extruder-upgrade_41560#42048, step 11 */ #if HAS_PRUSA_MMU2S #define MMU2_C0_RETRY 5 // Number of retries (total time = timeout*retries) + /** + * This is called after the filament runout sensor is triggered to check if + * the filament has been loaded properly by moving the filament back and + * forth to see if the filament runout sensor is going to get triggered + * again, which should not occur if the filament is properly loaded. + * + * Thus, the MMU2_CAN_LOAD_SEQUENCE should contain some forward and + * backward moves. The forward moves should be greater than the backward + * moves. + * + * This is useless if your filament runout sensor is way behind the gears. + * In that case use {0, MMU2_CAN_LOAD_FEEDRATE} + * + * Adjust MMU2_CAN_LOAD_SEQUENCE according to your setup. + */ #define MMU2_CAN_LOAD_FEEDRATE 800 // (mm/min) #define MMU2_CAN_LOAD_SEQUENCE \ - { 0.1, MMU2_CAN_LOAD_FEEDRATE }, \ - { 60.0, MMU2_CAN_LOAD_FEEDRATE }, \ - { -52.0, MMU2_CAN_LOAD_FEEDRATE } + { 5.0, MMU2_CAN_LOAD_FEEDRATE }, \ + { 15.0, MMU2_CAN_LOAD_FEEDRATE }, \ + { -10.0, MMU2_CAN_LOAD_FEEDRATE } #define MMU2_CAN_LOAD_RETRACT 6.0 // (mm) Keep under the distance between Load Sequence values #define MMU2_CAN_LOAD_DEVIATION 0.8 // (mm) Acceptable deviation @@ -4242,10 +4634,92 @@ #define MMU2_CAN_LOAD_INCREMENT_SEQUENCE \ { -MMU2_CAN_LOAD_INCREMENT, MMU2_CAN_LOAD_FEEDRATE } - #else + // Continue unloading if sensor detects filament after the initial unload move + //#define MMU_IR_UNLOAD_MOVE + + #elif HAS_PRUSA_MMU3 + + // MMU3 settings + + #define MMU3_HAS_CUTTER // Enable cutter related functionality + + #define MMU3_MAX_RETRIES 3 // Number of retries (total time = timeout*retries) + + // As discussed with our PrusaSlicer profile specialist + // - ToolChange shall not try to push filament into the very tip of the nozzle + // to have some space for additional G-code to tune the extruded filament length + // in the profile + // Beware - this value is used to initialize the MMU logic layer - it will be sent to the MMU upon line up (written into its 8bit register 0x0b) + // However - in the G-code we can get a request to set the extra load distance at runtime to something else (M708 A0xb Xsomething). + // The printer intercepts such a call and sets its extra load distance to match the new value as well. + #define MMU3_FILAMENT_SENSOR_E_POSITION 0 // (mm) + #define _MMU3_LOAD_DISTANCE_PAST_GEARS 5 // (mm) + #define MMU3_TOOL_CHANGE_LOAD_LENGTH (MMU3_FILAMENT_SENSOR_E_POSITION + _MMU3_LOAD_DISTANCE_PAST_GEARS) // (mm) + + #define MMU3_LOAD_TO_NOZZLE_FEED_RATE 20.0 // (mm/s) + + #define MMU3_VERIFY_LOAD_TO_NOZZLE_FEED_RATE 50.0 // (mm/s) + #define _MMU3_VERIFY_LOAD_TO_NOZZLE_TWEAK -5.0 // (mm) Amount to adjust the length for verifying load-to-nozzle + + // The first thing the MMU does is initialize its axis. + // Meanwhile the E-motor will unload 20mm of filament in about 1 second. + #define MMU3_RETRY_UNLOAD_TO_FINDA_LENGTH 80.0 // (mm) + #define MMU3_RETRY_UNLOAD_TO_FINDA_FEED_RATE 80.0 // (mm/s) + + // After loading a new filament, the printer will extrude this length of filament + // then retract to the original position. This is used to check if the filament sensor + // reading flickers or filament is jammed. + #define _MMU_EXTRUDER_PTFE_LENGTH 42.3 // (mm) + #define _MMU_EXTRUDER_HEATBREAK_LENGTH 17.7 // (mm) + #define MMU3_CHECK_FILAMENT_PRESENCE_EXTRUSION_LENGTH (MMU3_FILAMENT_SENSOR_E_POSITION + _MMU_EXTRUDER_PTFE_LENGTH + _MMU_EXTRUDER_HEATBREAK_LENGTH + _MMU3_VERIFY_LOAD_TO_NOZZLE_TWEAK) // (mm) /** - * MMU1 Extruder Sensor + * SpoolJoin Consumes All Filament -- EXPERIMENTAL + * + * SpoolJoin normally triggers when FINDA sensor untriggers while printing. + * This is the default behaviour and it doesn't consume all the filament + * before triggering a filament change. This leaves some filament in the + * current slot and before switching to the next slot it is unloaded. + * + * Enabling this option will trigger the filament change when both FINDA + * and Filament Runout Sensor triggers during the print and it allows the + * filament in the current slot to be completely consumed before doing the + * filament change. But this can cause problems as a little bit of filament + * will be left between the extruder gears (thinking that the filament + * sensor is triggered through the gears) and the end of the PTFE tube and + * can cause filament load issues. + */ + //#define MMU3_SPOOL_JOIN_CONSUMES_ALL_FILAMENT + + // MMU3 sequences use mm/sec. Not compatible with MMU2 which use mm/min. + #define MMU3_LOAD_TO_NOZZLE_SEQUENCE \ + { _MMU_EXTRUDER_PTFE_LENGTH, MMM_TO_MMS(810) }, /* (13.5 mm/s) Fast load ahead of heatbreak */ \ + { _MMU_EXTRUDER_HEATBREAK_LENGTH, MMM_TO_MMS(198) } /* ( 3.3 mm/s) Slow load after heatbreak */ + + #define MMU3_RAMMING_SEQUENCE \ + { 0.2816, MMM_TO_MMS(1339.0) }, \ + { 0.3051, MMM_TO_MMS(1451.0) }, \ + { 0.3453, MMM_TO_MMS(1642.0) }, \ + { 0.3990, MMM_TO_MMS(1897.0) }, \ + { 0.4761, MMM_TO_MMS(2264.0) }, \ + { 0.5767, MMM_TO_MMS(2742.0) }, \ + { 0.5691, MMM_TO_MMS(3220.0) }, \ + { 0.1081, MMM_TO_MMS(3220.0) }, \ + { 0.7644, MMM_TO_MMS(3635.0) }, \ + { 0.8248, MMM_TO_MMS(3921.0) }, \ + { 0.8483, MMM_TO_MMS(4033.0) }, \ + { -15.0, MMM_TO_MMS(6000.0) }, \ + { -24.5, MMM_TO_MMS(1200.0) }, \ + { -7.0, MMM_TO_MMS( 600.0) }, \ + { -3.5, MMM_TO_MMS( 360.0) }, \ + { 20.0, MMM_TO_MMS( 454.0) }, \ + { -20.0, MMM_TO_MMS( 303.0) }, \ + { -35.0, MMM_TO_MMS(2000.0) } + + #else // MMU2 (not MMU2S) + + /** + * MMU2 Extruder Sensor * * Support for a Průša (or other) IR Sensor to detect filament near the extruder * and make loading more reliable. Suitable for an extruder equipped with a filament @@ -4255,16 +4729,14 @@ * move up to the gears. If no filament is detected, the MMU2 can make some more attempts. * If all attempts fail, a filament runout will be triggered. */ - //#define MMU_EXTRUDER_SENSOR - #if ENABLED(MMU_EXTRUDER_SENSOR) - #define MMU_LOADING_ATTEMPTS_NR 5 // max. number of attempts to load filament if first load fail + //#define MMU2_EXTRUDER_SENSOR + #if ENABLED(MMU2_EXTRUDER_SENSOR) + #define MMU2_LOADING_ATTEMPTS_NR 5 // Number of times to try loading filament before failure #endif #endif - //#define MMU2_DEBUG // Write debug info to serial output - -#endif // HAS_PRUSA_MMU2 +#endif // HAS_PRUSA_MMU2 || HAS_PRUSA_MMU3 /** * Advanced Print Counter settings @@ -4298,6 +4770,11 @@ // //#define PINS_DEBUGGING +// +// M265 - I2C Scanner +// +//#define I2C_SCANNER + // Enable Tests that will run at startup and produce a report //#define MARLIN_TEST_BUILD @@ -4327,3 +4804,6 @@ // Report uncleaned reset reason from register r2 instead of MCUSR. Supported by Optiboot on AVR. //#define OPTIBOOT_RESET_REASON + +// Shrink the build for smaller boards by sacrificing some serial feedback +//#define MARLIN_SMALL_BUILD diff --git a/Marlin/Makefile b/Marlin/Makefile index c72c1d5896..aed2506ac8 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -63,8 +63,8 @@ HARDWARE_MOTHERBOARD ?= 1020 ifeq ($(OS),Windows_NT) # Windows - ARDUINO_INSTALL_DIR ?= ${HOME}/Arduino - ARDUINO_USER_DIR ?= ${HOME}/Arduino + ARDUINO_INSTALL_DIR ?= ${HOME}/AppData/Local/Arduino + ARDUINO_USER_DIR ?= ${HOME}/Documents/Arduino else UNAME_S := $(shell uname -s) ifeq ($(UNAME_S),Linux) @@ -82,11 +82,11 @@ endif # Arduino source install directory, and version number # On most linuxes this will be /usr/share/arduino -ARDUINO_INSTALL_DIR ?= ${HOME}/Arduino -ARDUINO_VERSION ?= 106 +ARDUINO_INSTALL_DIR ?= ${HOME}/AppData/Local/Arduino # C:/Users/${USERNAME}/AppData/Local/Arduino +ARDUINO_VERSION ?= 10819 # The installed Libraries are in the User folder -ARDUINO_USER_DIR ?= ${HOME}/Arduino +ARDUINO_USER_DIR ?= ${HOME}/Documents/Arduino # You can optionally set a path to the avr-gcc tools. # Requires a trailing slash. For example, /usr/local/avr-gcc/bin/ @@ -127,9 +127,9 @@ NEOPIXEL ?= 0 # on GCC versions: # https://www.avrfreaks.net/comment/1789106#comment-1789106 -CC_MAJ:=$(shell $(CC) -dM -E - < /dev/null | grep __GNUC__ | cut -f3 -d\ ) -CC_MIN:=$(shell $(CC) -dM -E - < /dev/null | grep __GNUC_MINOR__ | cut -f3 -d\ ) -CC_PATCHLEVEL:=$(shell $(CC) -dM -E - < /dev/null | grep __GNUC_PATCHLEVEL__ | cut -f3 -d\ ) +CC_MAJ:=$(shell $(CC) -dM -E - < /dev/null | grep __GNUC__ | cut -f3 -d' ' ) +CC_MIN:=$(shell $(CC) -dM -E - < /dev/null | grep __GNUC_MINOR__ | cut -f3 -d' ' ) +CC_PATCHLEVEL:=$(shell $(CC) -dM -E - < /dev/null | grep __GNUC_PATCHLEVEL__ | cut -f3 -d' ' ) CC_VER:=$(shell echo $$(( $(CC_MAJ) * 10000 + $(CC_MIN) * 100 + $(CC_PATCHLEVEL) ))) ifeq ($(shell test $(CC_VER) -lt 40901 && echo 1),1) $(warning This GCC version $(CC_VER) is likely broken. Enabling relocation workaround.) @@ -187,6 +187,17 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1033) # RAMPS Plus 3DYMY (Power outputs: Spindle, Controller Fan) else ifeq ($(HARDWARE_MOTHERBOARD),1034) +# RAMPS 1.6+ (Power outputs: Hotend, Fan, Bed) +else ifeq ($(HARDWARE_MOTHERBOARD),1040) +# RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Bed) +else ifeq ($(HARDWARE_MOTHERBOARD),1041) +# RAMPS 1.6+ (Power outputs: Hotend, Fan0, Fan1) +else ifeq ($(HARDWARE_MOTHERBOARD),1042) +# RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Fan) +else ifeq ($(HARDWARE_MOTHERBOARD),1043) +# RAMPS 1.6+ (Power outputs: Spindle, Controller Fan) +else ifeq ($(HARDWARE_MOTHERBOARD),1044) + # # RAMPS Derivatives - ATmega1280, ATmega2560 # @@ -221,79 +232,79 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1112) else ifeq ($(HARDWARE_MOTHERBOARD),1113) # BigTreeTech or BIQU KFB2.0 else ifeq ($(HARDWARE_MOTHERBOARD),1114) -# zrib V2.0 (Chinese RAMPS replica) +# Zonestar zrib V2.0 (Chinese RAMPS replica) else ifeq ($(HARDWARE_MOTHERBOARD),1115) -# zrib V5.2 (Chinese RAMPS replica) +# Zonestar zrib V5.2 (Chinese RAMPS replica) else ifeq ($(HARDWARE_MOTHERBOARD),1116) -# Felix 2.0+ Electronics Board (RAMPS like) +# Zonestar zrib V5.3 (Chinese RAMPS replica) else ifeq ($(HARDWARE_MOTHERBOARD),1117) -# Invent-A-Part RigidBoard +# Felix 2.0+ Electronics Board (RAMPS like) else ifeq ($(HARDWARE_MOTHERBOARD),1118) -# Invent-A-Part RigidBoard V2 +# Invent-A-Part RigidBoard else ifeq ($(HARDWARE_MOTHERBOARD),1119) -# Sainsmart 2-in-1 board +# Invent-A-Part RigidBoard V2 else ifeq ($(HARDWARE_MOTHERBOARD),1120) -# Ultimaker +# Sainsmart 2-in-1 board else ifeq ($(HARDWARE_MOTHERBOARD),1121) -# Ultimaker (Older electronics. Pre 1.5.4. This is rare) +# Ultimaker else ifeq ($(HARDWARE_MOTHERBOARD),1122) +# Ultimaker (Older electronics. Pre 1.5.4. This is rare) +else ifeq ($(HARDWARE_MOTHERBOARD),1123) MCU ?= atmega1280 PROG_MCU ?= m1280 # Azteeg X3 -else ifeq ($(HARDWARE_MOTHERBOARD),1123) -# Azteeg X3 Pro else ifeq ($(HARDWARE_MOTHERBOARD),1124) -# Ultimainboard 2.x (Uses TEMP_SENSOR 20) +# Azteeg X3 Pro else ifeq ($(HARDWARE_MOTHERBOARD),1125) -# Rumba +# Ultimainboard 2.x (Uses TEMP_SENSOR 20) else ifeq ($(HARDWARE_MOTHERBOARD),1126) -# Raise3D N series Rumba derivative +# Rumba else ifeq ($(HARDWARE_MOTHERBOARD),1127) -# Rapide Lite 200 (v1, low-cost RUMBA clone with drv) +# Raise3D N series Rumba derivative else ifeq ($(HARDWARE_MOTHERBOARD),1128) -# Formbot T-Rex 2 Plus +# Rapide Lite 200 (v1, low-cost RUMBA clone with drv) else ifeq ($(HARDWARE_MOTHERBOARD),1129) -# Formbot T-Rex 3 +# Formbot T-Rex 2 Plus else ifeq ($(HARDWARE_MOTHERBOARD),1130) -# Formbot Raptor +# Formbot T-Rex 3 else ifeq ($(HARDWARE_MOTHERBOARD),1131) -# Formbot Raptor 2 +# Formbot Raptor else ifeq ($(HARDWARE_MOTHERBOARD),1132) -# bq ZUM Mega 3D +# Formbot Raptor 2 else ifeq ($(HARDWARE_MOTHERBOARD),1133) -# MakeBoard Mini v2.1.2 by MicroMake +# bq ZUM Mega 3D else ifeq ($(HARDWARE_MOTHERBOARD),1134) -# TriGorilla Anycubic version 1.3-based on RAMPS EFB +# MakeBoard Mini v2.1.2 by MicroMake else ifeq ($(HARDWARE_MOTHERBOARD),1135) -# ... Ver 1.4 +# TriGorilla Anycubic version 1.3-based on RAMPS EFB else ifeq ($(HARDWARE_MOTHERBOARD),1136) -# ... Rev 1.1 (new servo pin order) +# ... Ver 1.4 else ifeq ($(HARDWARE_MOTHERBOARD),1137) -# Creality: Ender-4, CR-8 +# ... Rev 1.1 (new servo pin order) else ifeq ($(HARDWARE_MOTHERBOARD),1138) -# Creality: CR10S, CR20, CR-X +# Creality: Ender-4, CR-8 else ifeq ($(HARDWARE_MOTHERBOARD),1139) -# Dagoma F5 +# Creality: CR10S, CR20, CR-X else ifeq ($(HARDWARE_MOTHERBOARD),1140) -# FYSETC F6 1.3 +# Creality CR-10 V2, CR-10 V3 else ifeq ($(HARDWARE_MOTHERBOARD),1141) -# FYSETC F6 1.4 +# Dagoma F5 else ifeq ($(HARDWARE_MOTHERBOARD),1142) -# Wanhao Duplicator i3 Plus +# Dagoma D6 (as found in the Dagoma DiscoUltimate V2 TMC) else ifeq ($(HARDWARE_MOTHERBOARD),1143) -# VORON Design +# FYSETC F6 1.3 else ifeq ($(HARDWARE_MOTHERBOARD),1144) -# Tronxy TRONXY-V3-1.0 +# FYSETC F6 1.4 else ifeq ($(HARDWARE_MOTHERBOARD),1145) -# Z-Bolt X Series +# Wanhao Duplicator i3 Plus else ifeq ($(HARDWARE_MOTHERBOARD),1146) -# TT OSCAR +# VORON Design else ifeq ($(HARDWARE_MOTHERBOARD),1147) -# Overlord/Overlord Pro +# Tronxy TRONXY-V3-1.0 else ifeq ($(HARDWARE_MOTHERBOARD),1148) -# ADIMLab Gantry v1 +# Z-Bolt X Series else ifeq ($(HARDWARE_MOTHERBOARD),1149) -# ADIMLab Gantry v2 +# TT OSCAR else ifeq ($(HARDWARE_MOTHERBOARD),1150) # BIQU Tango V1 else ifeq ($(HARDWARE_MOTHERBOARD),1151) @@ -307,20 +318,30 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1154) else ifeq ($(HARDWARE_MOTHERBOARD),1155) # Tenlog D3 Hero IDEX printer else ifeq ($(HARDWARE_MOTHERBOARD),1156) -# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed) +# Tenlog D3, D5, D6 IDEX Printer else ifeq ($(HARDWARE_MOTHERBOARD),1157) -# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed) else ifeq ($(HARDWARE_MOTHERBOARD),1158) -# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed) else ifeq ($(HARDWARE_MOTHERBOARD),1159) -# Longer LK1 PRO / Alfawise U20 Pro (PRO version) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed) else ifeq ($(HARDWARE_MOTHERBOARD),1160) -# Longer LKx PRO / Alfawise Uxx Pro (PRO version) +# Longer LK1 PRO / Alfawise U20 Pro (PRO version) else ifeq ($(HARDWARE_MOTHERBOARD),1161) -# Zonestar zrib V5.3 (Chinese RAMPS replica) +# Longer LKx PRO / Alfawise Uxx Pro (PRO version) else ifeq ($(HARDWARE_MOTHERBOARD),1162) # Pxmalion Core I3 else ifeq ($(HARDWARE_MOTHERBOARD),1163) +# Panowin Cutlass (as found in the Panowin F1) +else ifeq ($(HARDWARE_MOTHERBOARD),1164) +# Kodama Bardo V1.x (as found in the Kodama Trinus) +else ifeq ($(HARDWARE_MOTHERBOARD),1165) +# XTLW MFF V1.0 +else ifeq ($(HARDWARE_MOTHERBOARD),1166) +# XTLW MFF V2.0 +else ifeq ($(HARDWARE_MOTHERBOARD),1167) +# E3D Rumba BigBox +else ifeq ($(HARDWARE_MOTHERBOARD),1168) # # RAMBo and derivatives @@ -338,7 +359,7 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1203) else ifeq ($(HARDWARE_MOTHERBOARD),1204) # abee Scoovo X9H else ifeq ($(HARDWARE_MOTHERBOARD),1205) -# Rambo ThinkerV2 +# ThinkerV2 else ifeq ($(HARDWARE_MOTHERBOARD),1206) # @@ -381,30 +402,42 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1315) else ifeq ($(HARDWARE_MOTHERBOARD),1316) # Geeetech GT2560 Rev B for A10(M/T/D) else ifeq ($(HARDWARE_MOTHERBOARD),1317) -# Geeetech GT2560 Rev B for A10(M/T/D) -else ifeq ($(HARDWARE_MOTHERBOARD),1318) # Geeetech GT2560 Rev B for Mecreator2 +else ifeq ($(HARDWARE_MOTHERBOARD),1318) +# Geeetech GT2560 Rev B for A20(M/T/D) else ifeq ($(HARDWARE_MOTHERBOARD),1319) -# Geeetech GT2560 Rev B for A20(M/T/D) +# Geeetech GT2560 Rev B for A10(M/T/D) else ifeq ($(HARDWARE_MOTHERBOARD),1320) -# Einstart retrofit -else ifeq ($(HARDWARE_MOTHERBOARD),1321) -# Wanhao 0ne+ i3 Mini -else ifeq ($(HARDWARE_MOTHERBOARD),1322) -# Leapfrog Xeed 2015 -else ifeq ($(HARDWARE_MOTHERBOARD),1323) -# PICA Shield (original version) -else ifeq ($(HARDWARE_MOTHERBOARD),1324) -# PICA Shield (rev C or later) -else ifeq ($(HARDWARE_MOTHERBOARD),1325) -# Intamsys 4.0 (Funmat HT) -else ifeq ($(HARDWARE_MOTHERBOARD),1326) -# Malyan M180 Mainboard Version 2 (no display function, direct G-code only) -else ifeq ($(HARDWARE_MOTHERBOARD),1327) # Geeetech GT2560 Rev B for A20(M/T/D) +else ifeq ($(HARDWARE_MOTHERBOARD),1321) +# Geeetech GT2560 V4.1B for A10(M/T/D) +else ifeq ($(HARDWARE_MOTHERBOARD),1322) +# Einstart retrofit +else ifeq ($(HARDWARE_MOTHERBOARD),1323) +# Wanhao 0ne+ i3 Mini +else ifeq ($(HARDWARE_MOTHERBOARD),1324) +# Wanhao D9 MK2 +else ifeq ($(HARDWARE_MOTHERBOARD),1325) +# Overlord/Overlord Pro +else ifeq ($(HARDWARE_MOTHERBOARD),1326) +# ADIMLab Gantry v1 +else ifeq ($(HARDWARE_MOTHERBOARD),1327) +# ADIMLab Gantry v2 else ifeq ($(HARDWARE_MOTHERBOARD),1328) -# Mega controller & Protoneer CNC Shield V3.00 +# Leapfrog Xeed 2015 else ifeq ($(HARDWARE_MOTHERBOARD),1329) +# PICA Shield (original version) +else ifeq ($(HARDWARE_MOTHERBOARD),1330) +# PICA Shield (rev C or later) +else ifeq ($(HARDWARE_MOTHERBOARD),1331) +# Intamsys 4.0 (Funmat HT) +else ifeq ($(HARDWARE_MOTHERBOARD),1332) +# Malyan M180 Mainboard Version 2 +else ifeq ($(HARDWARE_MOTHERBOARD),1333) +# Mega controller & Protoneer CNC Shield V3.00 +else ifeq ($(HARDWARE_MOTHERBOARD),1334) +# WEEDO 62A board (TINA2, Monoprice Cadet, etc.) +else ifeq ($(HARDWARE_MOTHERBOARD),1335) # # ATmega1281, ATmega2561 @@ -438,7 +471,7 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1502) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega644p PROG_MCU ?= m644p -# Melzi V2.0 +# Melzi V2 else ifeq ($(HARDWARE_MOTHERBOARD),1503) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p @@ -448,41 +481,46 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1504) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p -# Melzi Creality3D board (for CR-10 etc) +# Melzi Creality3D (for CR-10 etc) else ifeq ($(HARDWARE_MOTHERBOARD),1505) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p -# Melzi Malyan M150 board +# Melzi Creality3D (for Ender-2) else ifeq ($(HARDWARE_MOTHERBOARD),1506) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p -# Tronxy X5S +# Melzi Malyan M150 else ifeq ($(HARDWARE_MOTHERBOARD),1507) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p -# STB V1.1 +# Tronxy X5S else ifeq ($(HARDWARE_MOTHERBOARD),1508) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p -# Azteeg X1 +# STB V1.1 else ifeq ($(HARDWARE_MOTHERBOARD),1509) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p -# Anet 1.0 (Melzi clone) +# Azteeg X1 else ifeq ($(HARDWARE_MOTHERBOARD),1510) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p -# ZoneStar ZMIB V2 +# Anet 1.0 (Melzi clone) else ifeq ($(HARDWARE_MOTHERBOARD),1511) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p +# ZoneStar ZMIB V2 +else ifeq ($(HARDWARE_MOTHERBOARD),1512) + HARDWARE_VARIANT ?= Sanguino + MCU ?= atmega1284p + PROG_MCU ?= m1284p # # Other ATmega644P, ATmega644, ATmega1284P @@ -593,6 +631,10 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1707) MCU ?= at90usb1286 PROG_MCU ?= usb1286 +# +# SAM3X8E ARM Cortex-M3 +# + # UltiMachine Archim1 (with DRV8825 drivers) else ifeq ($(HARDWARE_MOTHERBOARD),3023) HARDWARE_VARIANT ?= archim @@ -654,18 +696,18 @@ ifeq ($(HARDWARE_VARIANT), $(filter $(HARDWARE_VARIANT),arduino Teensy Sanguino) # Old libraries (avr-core 1.6.21 < / Arduino < 1.6.8) VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SPI # New libraries (avr-core >= 1.6.21 / Arduino >= 1.6.8) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SPI/src + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/arduino/avr/1.8.6/libraries/SPI/src endif ifeq ($(IS_MCU),1) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/cores/arduino + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/arduino/avr/1.8.6/cores/arduino # Old libraries (avr-core 1.6.21 < / Arduino < 1.6.8) VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SPI VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SoftwareSerial # New libraries (avr-core >= 1.6.21 / Arduino >= 1.6.8) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SPI/src - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SoftwareSerial/src + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/arduino/avr/1.8.6/libraries/SPI/src + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/arduino/avr/1.8.6/libraries/SoftwareSerial/src endif VPATH += $(ARDUINO_INSTALL_DIR)/libraries/LiquidCrystal/src @@ -679,17 +721,17 @@ ifeq ($(WIRE), 1) VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/Wire VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/Wire/utility # New libraries (avr-core >= 1.6.21 / Arduino >= 1.6.8) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/Wire/src - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/Wire/src/utility + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/libraries/Wire/src + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/libraries/Wire/src/utility endif ifeq ($(NEOPIXEL), 1) VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Adafruit_NeoPixel endif ifeq ($(U8GLIB), 1) -VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib -VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/csrc -VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/cppsrc -VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/fntsrc +VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib-HAL +VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib-HAL/src +# VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib +# VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/src endif ifeq ($(TMC), 1) VPATH += $(ARDUINO_INSTALL_DIR)/libraries/TMCStepper/src @@ -698,9 +740,9 @@ endif ifeq ($(HARDWARE_VARIANT), arduino) HARDWARE_SUB_VARIANT ?= mega - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/variants/$(HARDWARE_SUB_VARIANT) + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/variants/$(HARDWARE_SUB_VARIANT) else ifeq ($(HARDWARE_VARIANT), Sanguino) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/marlin/avr/variants/sanguino + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/variants/sanguino else ifeq ($(HARDWARE_VARIANT), archim) VPATH += $(ARDUINO_INSTALL_DIR)/packages/ultimachine/hardware/sam/1.6.9-b/system/libsam VPATH += $(ARDUINO_INSTALL_DIR)/packages/ultimachine/hardware/sam/1.6.9-b/system/CMSIS/CMSIS/Include/ @@ -716,7 +758,7 @@ else ifeq ($(HARDWARE_VARIANT), archim) LDLIBS = $(ARDUINO_INSTALL_DIR)/packages/ultimachine/hardware/sam/1.6.9-b/variants/archim/libsam_sam3x8e_gcc_rel.a else HARDWARE_SUB_VARIANT ?= standard - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/$(HARDWARE_VARIANT)/variants/$(HARDWARE_SUB_VARIANT) + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/variants/$(HARDWARE_SUB_VARIANT) endif LIB_SRC = wiring.c \ @@ -731,7 +773,7 @@ endif ifeq ($(HARDWARE_VARIANT), Teensy) LIB_SRC = wiring.c - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/teensy/cores/teensy + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/teensy/cores/teensy endif LIB_CXXSRC = WMath.cpp WString.cpp Print.cpp SPI.cpp @@ -765,10 +807,10 @@ endif ifeq ($(TMC), 1) LIB_CXXSRC += TMCStepper.cpp COOLCONF.cpp DRV_STATUS.cpp IHOLD_IRUN.cpp \ - CHOPCONF.cpp GCONF.cpp PWMCONF.cpp DRV_CONF.cpp DRVCONF.cpp DRVCTRL.cpp \ - DRVSTATUS.cpp ENCMODE.cpp RAMP_STAT.cpp SGCSCONF.cpp SHORT_CONF.cpp \ - SMARTEN.cpp SW_MODE.cpp SW_SPI.cpp TMC2130Stepper.cpp TMC2208Stepper.cpp \ - TMC2209Stepper.cpp TMC2660Stepper.cpp TMC5130Stepper.cpp TMC5160Stepper.cpp + CHOPCONF.cpp GCONF.cpp PWMCONF.cpp DRV_CONF.cpp DRVCONF.cpp DRVCTRL.cpp DRVSTATUS.cpp \ + GLOBAL_SCALER.cpp SLAVECONF.cpp IOIN.cpp ENCMODE.cpp RAMP_STAT.cpp SGCSCONF.cpp \ + SHORT_CONF.cpp SMARTEN.cpp SW_MODE.cpp SW_SPI.cpp TMC2130Stepper.cpp TMC2208Stepper.cpp \ + TMC2209Stepper.cpp TMC2240Stepper.cpp TMC2660Stepper.cpp TMC5130Stepper.cpp TMC5160Stepper.cpp endif ifeq ($(RELOC_WORKAROUND), 1) @@ -835,8 +877,8 @@ else ifeq ($(HARDWARE_VARIANT), archim) endif # Add all the source directories as include directories too -CINCS = ${addprefix -I ,${VPATH}} -CXXINCS = ${addprefix -I ,${VPATH}} +CINCS = ${addprefix -I, ${VPATH}} +CXXINCS = ${addprefix -I, ${VPATH}} # Silence warnings for library code (won't work for .h files, unfortunately) LIBWARN = -w -Wno-packed-bitfield-compat @@ -878,7 +920,7 @@ AVRDUDE_WRITE_FLASH = -Uflash:w:$(BUILD_DIR)/$(TARGET).hex:i ifeq ($(shell uname -s), Linux) AVRDUDE_CONF = /etc/avrdude/avrdude.conf else - AVRDUDE_CONF = $(ARDUINO_INSTALL_DIR)/hardware/tools/avr/etc/avrdude.conf + AVRDUDE_CONF = $(ARDUINO_INSTALL_DIR)/packages/arduino/tools/avrdude/6.3.0-arduino17/etc/avrdude.conf endif AVRDUDE_FLAGS = -D -C$(AVRDUDE_CONF) \ -p$(PROG_MCU) -P$(AVRDUDE_PORT) -c$(AVRDUDE_PROGRAMMER) \ @@ -993,7 +1035,7 @@ extcoff: $(TARGET).elf $(NM) -n $< > $@ # Link: create ELF output file from library. - +LDFLAGS+= -Wl,-V $(BUILD_DIR)/$(TARGET).elf: $(OBJ) Configuration.h $(Pecho) " CXX $@" $P $(CXX) $(LD_PREFIX) $(ALL_CXXFLAGS) -o $@ -L. $(OBJ) $(LDFLAGS) $(LD_SUFFIX) diff --git a/Marlin/Marlin.ino b/Marlin/Marlin.ino index 57c825445f..066cc1717d 100644 --- a/Marlin/Marlin.ino +++ b/Marlin/Marlin.ino @@ -2,7 +2,7 @@ Marlin Firmware - (c) 2011-2020 MarlinFirmware + (c) 2011-2024 MarlinFirmware Portions of Marlin are (c) by their respective authors. All code complies with GPLv2 and/or GPLv3 @@ -27,7 +27,7 @@ Configuration - https://github.com/MarlinFirmware/Configurations Example configurations for several printer models. - - https://www.youtube.com/watch?v=3gwWVFtdg-4 + - https://youtu.be/3gwWVFtdg-4 A good 20-minute overview of Marlin configuration by Tom Sanladerer. (Applies to Marlin 1.0.x, so Jerk and Acceleration should be halved.) Also... https://www.google.com/search?tbs=vid%3A1&q=configure+marlin diff --git a/Marlin/Version.h b/Marlin/Version.h index d9ec298ede..d257cd11f5 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.1.1" +//#define SHORT_BUILD_VERSION "bugfix-2.1.x" /** * Verbose version identifier which should contain a reference to the location @@ -41,7 +41,14 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-08-06" +//#define STRING_DISTRIBUTION_DATE "2026-01-12" + +/** + * The protocol for communication to the host. Protocol indicates communication + * standards such as the use of ASCII, "echo:" and "error:" line prefixes, etc. + * (Other behaviors are given by the firmware version and capabilities report.) + */ +//#define PROTOCOL_VERSION "1.0" /** * Defines a generic printer name to be output to the LCD after booting Marlin. @@ -51,7 +58,7 @@ /** * The SOURCE_CODE_URL is the location where users will find the Marlin Source * Code which is installed on the device. In most cases —unless the manufacturer - * has a distinct Github fork— the Source Code URL should just be the main + * has a distinct GitHub fork— the Source Code URL should just be the main * Marlin repository. */ //#define SOURCE_CODE_URL "github.com/MarlinFirmware/Marlin" @@ -68,8 +75,8 @@ //#define WEBSITE_URL "marlinfw.org" /** - * Set the vendor info the serial USB interface, if changable - * Currently only supported by DUE platform + * Set the vendor info the serial USB interface, if changeable. + * Currently only supported by DUE platform. */ //#define USB_DEVICE_VENDOR_ID 0x0000 //#define USB_DEVICE_PRODUCT_ID 0x0000 diff --git a/Marlin/config.ini b/Marlin/config.ini index 0fb9fb0c93..fd2b81062a 100644 --- a/Marlin/config.ini +++ b/Marlin/config.ini @@ -3,10 +3,50 @@ # config.ini - Options to apply before the build # [config:base] +# +# ini_use_config - A comma-separated list of actions to apply to the Configuration files. +# The actions will be applied in the listed order. +# - none +# Ignore this file and don't apply any configuration options +# +# - base +# Just apply the options in config:base to the configuration +# +# - minimal +# Just apply the options in config:minimal to the configuration +# +# - all +# Apply all 'config:*' sections in this file to the configuration +# +# - another.ini +# Load another INI file with a path relative to this config.ini file (i.e., within Marlin/) +# +# - https://me.myserver.com/path/to/configs +# Fetch configurations from any URL. +# +# - example/Creality/Ender-5 Plus @ bugfix-2.1.x +# Fetch example configuration files from the MarlinFirmware/Configurations repository +# https://raw.githubusercontent.com/MarlinFirmware/Configurations/bugfix-2.1.x/config/examples/Creality/Ender-5%20Plus/ +# +# - example/default @ release-2.0.9.7 +# Fetch default configuration files from the MarlinFirmware/Configurations repository +# https://raw.githubusercontent.com/MarlinFirmware/Configurations/release-2.0.9.7/config/default/ +# +# - [disable] +# Comment out all #defines in both Configuration.h and Configuration_adv.h. This is useful +# to start with a clean slate before applying any config: options, so only the options explicitly +# set in config.ini will be enabled in the configuration. +# +# - [flatten] (Not yet implemented) +# Produce a flattened set of Configuration.h and Configuration_adv.h files with only the enabled +# #defines and no comments. A clean look, but context-free. +# ini_use_config = none # Load all config: sections in this file ;ini_use_config = all +# Disable everything and apply subsequent config:base options +;ini_use_config = [disable], base # Load config file relative to Marlin/ ;ini_use_config = another.ini # Download configurations from GitHub @@ -22,6 +62,11 @@ motherboard = BOARD_RAMPS_14_EFB serial_port = 0 baudrate = 250000 +string_config_h_author = "(default from config.ini)" + +capabilities_report = on +extended_capabilities_report = on + use_watchdog = on thermal_protection_hotends = on thermal_protection_hysteresis = 4 @@ -37,18 +82,25 @@ temp_sensor_0 = 1 temp_hysteresis = 3 heater_0_mintemp = 5 heater_0_maxtemp = 275 -preheat_1_temp_hotend = 180 -bang_max = 255 pidtemp = on pid_k1 = 0.95 -pid_max = BANG_MAX -pid_functional_range = 10 +pid_max = 255 +pid_functional_range = 20 default_kp = 22.20 default_ki = 1.08 default_kd = 114.00 +temp_sensor_bed = 1 +bed_check_interval = 5000 +bed_mintemp = 5 +bed_maxtemp = 150 + +thermal_protection_bed = on +thermal_protection_bed_hysteresis = 2 +thermal_protection_bed_period = 20 + x_driver_type = A4988 y_driver_type = A4988 z_driver_type = A4988 @@ -69,13 +121,9 @@ x_home_dir = -1 y_home_dir = -1 z_home_dir = -1 -use_xmin_plug = on -use_ymin_plug = on -use_zmin_plug = on - -x_min_endstop_inverting = false -y_min_endstop_inverting = false -z_min_endstop_inverting = false +x_min_endstop_hit_state = HIGH +y_min_endstop_hit_state = HIGH +z_min_endstop_hit_state = HIGH default_axis_steps_per_unit = { 80, 80, 400, 500 } axis_relative_modes = { false, false, false, false } @@ -85,25 +133,20 @@ default_max_acceleration = { 3000, 3000, 100, 10000 } homing_feedrate_mm_m = { (50*60), (50*60), (4*60) } homing_bump_divisor = { 2, 2, 4 } -x_enable_on = 0 -y_enable_on = 0 -z_enable_on = 0 -e_enable_on = 0 +x_enable_on = LOW +y_enable_on = LOW +z_enable_on = LOW +e_enable_on = LOW invert_x_dir = false invert_y_dir = true invert_z_dir = false invert_e0_dir = false -invert_e_step_pin = false -invert_x_step_pin = false -invert_y_step_pin = false -invert_z_step_pin = false - -disable_x = false -disable_y = false -disable_z = false -disable_e = false +step_state_e = HIGH +step_state_x = HIGH +step_state_y = HIGH +step_state_z = HIGH proportional_font_ratio = 1.0 default_nominal_filament_dia = 1.75 @@ -117,30 +160,33 @@ default_retract_acceleration = 3000 default_minimumfeedrate = 0.0 default_mintravelfeedrate = 0.0 -minimum_planner_speed = 0.05 min_steps_per_segment = 6 default_minsegmenttime = 20000 [config:basic] +hotend_overshoot = 15 bed_overshoot = 10 +max_bed_power = 255 + busy_while_heating = on -default_ejerk = 5.0 +host_keepalive_feature = on default_keepalive_interval = 2 -default_leveling_fade_height = 0.0 -disable_inactive_extruder = on -display_charset_hd44780 = JAPANESE +printjob_timer_autostart = on + +jd_handle_small_segments = on +validate_homing_endstops = on +editable_steps_per_unit = on + eeprom_boot_silent = on eeprom_chitchat = on + endstoppullups = on -extrude_maxlength = 200 + +prevent_cold_extrusion = on extrude_mintemp = 170 -host_keepalive_feature = on -hotend_overshoot = 15 -jd_handle_small_segments = on -lcd_info_screen_style = 0 -lcd_language = en -max_bed_power = 255 -mesh_inset = 0 +prevent_lengthy_extrude = on +extrude_maxlength = 200 + min_software_endstops = on max_software_endstops = on min_software_endstop_x = on @@ -149,63 +195,60 @@ min_software_endstop_z = on max_software_endstop_x = on max_software_endstop_y = on max_software_endstop_z = on -preheat_1_fan_speed = 0 + preheat_1_label = "PLA" +preheat_1_temp_hotend = 180 preheat_1_temp_bed = 70 -prevent_cold_extrusion = on -prevent_lengthy_extrude = on -printjob_timer_autostart = on -probing_margin = 10 -show_bootscreen = on -soft_pwm_scale = 0 -string_config_h_author = "(none, default config)" +preheat_1_fan_speed = 0 + +preheat_2_label = "ABS" +preheat_2_temp_hotend = 240 +preheat_2_temp_bed = 110 +preheat_2_fan_speed = 0 + temp_bed_hysteresis = 3 temp_bed_residency_time = 10 temp_bed_window = 1 temp_residency_time = 10 temp_window = 1 -validate_homing_endstops = on -xy_probe_feedrate = (133*60) -z_clearance_between_probes = 5 -z_clearance_deploy_probe = 10 -z_clearance_multi_probe = 5 [config:advanced] arc_support = on -auto_report_temperatures = on -autotemp = on -autotemp_oldweight = 0.98 -bed_check_interval = 5000 -default_stepper_deactive_time = 120 -default_volumetric_extruder_limit = 0.00 -disable_inactive_e = true -disable_inactive_x = true -disable_inactive_y = true -disable_inactive_z = true -e0_auto_fan_pin = -1 -encoder_100x_steps_per_sec = 80 -encoder_10x_steps_per_sec = 30 -encoder_rate_multiplier = on -extended_capabilities_report = on -extruder_auto_fan_speed = 255 -extruder_auto_fan_temperature = 50 -fanmux0_pin = -1 -fanmux1_pin = -1 -fanmux2_pin = -1 -faster_gcode_parser = on -homing_bump_mm = { 5, 5, 2 } -max_arc_segment_mm = 1.0 min_arc_segment_mm = 0.1 +max_arc_segment_mm = 1.0 min_circle_segments = 72 n_arc_correction = 25 -serial_overrun_protection = on + +auto_report_temperatures = on + +autotemp = on +autotemp_min = 210 +autotemp_max = 250 +autotemp_factor = 0.1f +autotemp_oldweight = 0.98 + +default_stepper_timeout_sec = 120 +disable_idle_x = on +disable_idle_y = on +disable_idle_z = on +disable_idle_e = on + +e0_auto_fan_pin = -1 + +faster_gcode_parser = on +debug_flags_gcode = on + +homing_bump_mm = { 5, 5, 2 } + slowdown = on slowdown_divisor = 2 -temp_sensor_bed = 0 -thermal_protection_bed_hysteresis = 2 -thermocouple_max_errors = 15 +multistepping_limit = 16 + +serial_overrun_protection = on tx_buffer_size = 0 + +watch_temp_increase = 2 +watch_temp_period = 40 + watch_bed_temp_increase = 2 watch_bed_temp_period = 60 -watch_temp_increase = 2 -watch_temp_period = 20 diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 5382eb36a2..1fa7222711 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -61,23 +61,46 @@ void save_reset_reason() { wdt_disable(); } +#include "registers.h" + +MarlinHAL::MarlinHAL() { + TERN_(HAL_AVR_DIRTY_INIT, _ATmega_resetperipherals()); // Clean-wipe the device state. +} + void MarlinHAL::init() { // Init Servo Pins - #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #if HAS_SERVO_0 - INIT_SERVO(0); + OUT_WRITE(SERVO0_PIN, LOW); #endif #if HAS_SERVO_1 - INIT_SERVO(1); + OUT_WRITE(SERVO1_PIN, LOW); #endif #if HAS_SERVO_2 - INIT_SERVO(2); + OUT_WRITE(SERVO2_PIN, LOW); #endif #if HAS_SERVO_3 - INIT_SERVO(3); + OUT_WRITE(SERVO3_PIN, LOW); + #endif + #if HAS_SERVO_4 + OUT_WRITE(SERVO4_PIN, LOW); + #endif + #if HAS_SERVO_5 + OUT_WRITE(SERVO5_PIN, LOW); #endif init_pwm_timers(); // Init user timers to default frequency - 1000HZ + + #if PIN_EXISTS(BEEPER) && ENABLED(HAL_AVR_DIRTY_INIT) && DISABLED(ATMEGA_NO_BEEPFIX) + // Make sure no alternative is locked onto the BEEPER. + // This fixes the issue where the ATmega is constantly beeping. + // Might disable other peripherals using the pin; to circumvent that please undefine one of the above things! + // The true culprit is the AVR ArduinoCore that enables peripherals redundantly. + // (USART1 on the GeeeTech GT2560) + // https://youtube.be/jMgCvRXkexk + _ATmega_savePinAlternate(BEEPER_PIN); + + OUT_WRITE(BEEPER_PIN, LOW); + #endif } void MarlinHAL::reboot() { @@ -96,7 +119,6 @@ void MarlinHAL::reboot() { #if ENABLED(USE_WATCHDOG) #include - #include "../../MarlinCore.h" // Initialize watchdog with 8s timeout, if possible. Otherwise, make it 4s. void MarlinHAL::watchdog_init() { @@ -131,7 +153,7 @@ void MarlinHAL::reboot() { 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 + marlin.minkill(); // interrupt-safe final kill and infinite loop } #endif @@ -145,12 +167,12 @@ void MarlinHAL::reboot() { // Free Memory Accessor // ------------------------ -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../sd/SdFatUtil.h" int freeMemory() { return SdFatUtil::FreeRam(); } -#else // !SDSUPPORT +#else // !HAS_MEDIA extern "C" { extern char __bss_end; @@ -167,6 +189,6 @@ void MarlinHAL::reboot() { } } -#endif // !SDSUPPORT +#endif // !HAS_MEDIA #endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 1491867721..02c5d42beb 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -32,6 +34,7 @@ #include #else #include "MarlinSerial.h" + #define BOARD_NO_NATIVE_USB #endif #include @@ -106,48 +109,48 @@ typedef Servo hal_servo_t; #define MYSERIAL1 TERN(BLUETOOTH, btSerial, MSerial0) #else - #if !WITHIN(SERIAL_PORT, -1, 3) - #error "SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." + #if !WITHIN(SERIAL_PORT, 0, 3) + #error "SERIAL_PORT must be from 0 to 3." #endif #define MYSERIAL1 customizedSerial1 #ifdef SERIAL_PORT_2 - #if !WITHIN(SERIAL_PORT_2, -1, 3) - #error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial." + #if !WITHIN(SERIAL_PORT_2, 0, 3) + #error "SERIAL_PORT_2 must be from 0 to 3." #endif #define MYSERIAL2 customizedSerial2 #endif #ifdef SERIAL_PORT_3 - #if !WITHIN(SERIAL_PORT_3, -1, 3) - #error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial." + #if !WITHIN(SERIAL_PORT_3, 0, 3) + #error "SERIAL_PORT_3 must be from 0 to 3." #endif #define MYSERIAL3 customizedSerial3 #endif #endif -#ifdef MMU2_SERIAL_PORT - #if !WITHIN(MMU2_SERIAL_PORT, -1, 3) - #error "MMU2_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." +#ifdef MMU_SERIAL_PORT + #if !WITHIN(MMU_SERIAL_PORT, 0, 3) + #error "MMU_SERIAL_PORT must be from 0 to 3" #endif - #define MMU2_SERIAL mmuSerial + #define MMU_SERIAL mmuSerial #endif #ifdef LCD_SERIAL_PORT - #if !WITHIN(LCD_SERIAL_PORT, -1, 3) - #error "LCD_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." + #if !WITHIN(LCD_SERIAL_PORT, 0, 3) + #error "LCD_SERIAL_PORT must be from 0 to 3." #endif #define LCD_SERIAL lcdSerial - #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.get_tx_buffer_free() + #if ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.get_tx_buffer_free() #endif #endif // // ADC // -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_VREF_MV 5000 +#define HAL_ADC_RESOLUTION 10 // // Pin Mapping for M42, M43, M226 @@ -156,7 +159,7 @@ typedef Servo hal_servo_t; #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -#define HAL_SENSITIVE_PINS 0, 1, +#define HAL_SENSITIVE_PINS 0, 1 #ifdef __AVR_AT90USB1286__ #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) @@ -186,7 +189,7 @@ class MarlinHAL { public: // Earliest possible init, before setup() - MarlinHAL() {} + MarlinHAL(); // Watchdog static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); @@ -201,9 +204,9 @@ public: static void isr_on() { sei(); } static void isr_off() { cli(); } - static void delay_ms(const int ms) { _delay_ms(ms); } + static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index dc98f2f79e..db6a12734d 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -119,7 +119,6 @@ void spiBegin() { while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } - /** begin spi transaction */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // Based on Arduino SPI library @@ -175,7 +174,6 @@ void spiBegin() { SPSR = clockDiv | 0x01; } - #else // SOFTWARE_SPI || FORCE_SOFT_SPI // ------------------------ @@ -198,7 +196,7 @@ void spiBegin() { // output pin high - like sending 0xFF WRITE(SD_MOSI_PIN, HIGH); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { WRITE(SD_SCK_PIN, HIGH); nop; // adjust so SCK is nice @@ -225,7 +223,7 @@ void spiBegin() { void spiSend(uint8_t data) { // no interrupts during byte send - about 8µs cli(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { WRITE(SD_SCK_PIN, LOW); WRITE(SD_MOSI_PIN, data & 0x80); data <<= 1; diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 986462437c..750776c4be 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -41,7 +41,6 @@ #if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)) #include "MarlinSerial.h" -#include "../../MarlinCore.h" #if ENABLED(DIRECT_STEPPING) #include "../../feature/direct_stepping.h" @@ -601,20 +600,20 @@ MSerialT1 customizedSerial1(MSerialT1::HasEmergencyParser); #endif // SERIAL_PORT_3 -#ifdef MMU2_SERIAL_PORT +#ifdef MMU_SERIAL_PORT - ISR(SERIAL_REGNAME(USART, MMU2_SERIAL_PORT, _RX_vect)) { - MarlinSerial>::store_rxd_char(); + ISR(SERIAL_REGNAME(USART, MMU_SERIAL_PORT, _RX_vect)) { + MarlinSerial>::store_rxd_char(); } - ISR(SERIAL_REGNAME(USART, MMU2_SERIAL_PORT, _UDRE_vect)) { - MarlinSerial>::_tx_udr_empty_irq(); + ISR(SERIAL_REGNAME(USART, MMU_SERIAL_PORT, _UDRE_vect)) { + MarlinSerial>::_tx_udr_empty_irq(); } - template class MarlinSerial< MMU2SerialCfg >; + template class MarlinSerial< MMU2SerialCfg >; MSerialMMU2 mmuSerial(MSerialMMU2::HasEmergencyParser); -#endif // MMU2_SERIAL_PORT +#endif // MMU_SERIAL_PORT #ifdef LCD_SERIAL_PORT @@ -629,7 +628,7 @@ MSerialT1 customizedSerial1(MSerialT1::HasEmergencyParser); template class MarlinSerial< LCDSerialCfg >; MSerialLCD lcdSerial(MSerialLCD::HasEmergencyParser); - #if HAS_DGUS_LCD + #if ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) template typename MarlinSerial::ring_buffer_pos_t MarlinSerial::get_tx_buffer_free() { const ring_buffer_pos_t t = tx_buffer.tail, // next byte to send. diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index 7eb76000d6..9ecf3bde22 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -34,12 +34,9 @@ #include #include "../../inc/MarlinConfigPre.h" +#include "../../core/types.h" #include "../../core/serial_hook.h" -#ifndef SERIAL_PORT - #define SERIAL_PORT 0 -#endif - #ifndef USBCON // The presence of the UBRRH register is used to detect a UART. @@ -138,10 +135,6 @@ #define BYTE 0 - // Templated type selector - template struct TypeSelector { typedef T type;} ; - template struct TypeSelector { typedef F type; }; - template class MarlinSerial { protected: @@ -164,7 +157,7 @@ static constexpr B_U2Xx B_U2X = 0; // Base size of type on buffer size - typedef typename TypeSelector<(Cfg::RX_SIZE>256), uint16_t, uint8_t>::type ring_buffer_pos_t; + typedef uvalue_t(Cfg::RX_SIZE - 1) ring_buffer_pos_t; struct ring_buffer_r { volatile ring_buffer_pos_t head, tail; @@ -212,7 +205,7 @@ static ring_buffer_pos_t available(); static void write(const uint8_t c); static void flushTX(); - #if HAS_DGUS_LCD + #if ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) static ring_buffer_pos_t get_tx_buffer_free(); #endif @@ -253,7 +246,7 @@ #endif // !USBCON -#ifdef MMU2_SERIAL_PORT +#ifdef MMU_SERIAL_PORT template struct MMU2SerialCfg { static constexpr int PORT = serial; @@ -267,7 +260,7 @@ static constexpr bool RX_OVERRUNS = false; }; - typedef Serial1Class< MarlinSerial< MMU2SerialCfg > > MSerialMMU2; + typedef Serial1Class< MarlinSerial< MMU2SerialCfg > > MSerialMMU2; extern MSerialMMU2 mmuSerial; #endif @@ -283,7 +276,7 @@ static constexpr bool DROPPED_RX = false; static constexpr bool RX_FRAMING_ERRORS = false; static constexpr bool MAX_RX_QUEUED = false; - static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS); + static constexpr bool RX_OVERRUNS = ALL(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS); }; typedef Serial1Class< MarlinSerial< LCDSerialCfg > > MSerialLCD; diff --git a/Marlin/src/HAL/AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp index 0a1ef5337a..8ce9bc11b8 100644 --- a/Marlin/src/HAL/AVR/Servo.cpp +++ b/Marlin/src/HAL/AVR/Servo.cpp @@ -63,7 +63,6 @@ static volatile int8_t Channel[_Nbr_16timers]; // counter for the servo being pulsed for each timer (or -1 if refresh interval) - /************ static functions common to all instances ***********************/ static inline void handle_interrupts(const timer16_Sequence_t timer, volatile uint16_t* TCNTn, volatile uint16_t* OCRnA) { diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp index 8d084dec7f..45c7abd1db 100644 --- a/Marlin/src/HAL/AVR/eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +#if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) /** * PersistentStore for Arduino-style EEPROM interface @@ -35,14 +35,14 @@ #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(E2END + 1) #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { uint16_t written = 0; while (size--) { - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); uint8_t v = *value; if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); @@ -61,7 +61,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t c = eeprom_read_byte((uint8_t*)pos); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h index 5511aa406f..a6813ff277 100644 --- a/Marlin/src/HAL/AVR/endstop_interrupts.h +++ b/Marlin/src/HAL/AVR/endstop_interrupts.h @@ -91,7 +91,6 @@ void endstop_ISR() { endstops.update(); } #endif - // Install Pin change interrupt for a pin. Can be called multiple times. void pciSetup(const int8_t pin) { if (digitalPinHasPCICR(pin)) { @@ -120,7 +119,7 @@ void pciSetup(const int8_t pin) { void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - #if HAS_X_MAX + #if USE_X_MAX #if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(X_MAX_PIN); #else @@ -128,7 +127,7 @@ void setup_endstop_interrupts() { pciSetup(X_MAX_PIN); #endif #endif - #if HAS_X_MIN + #if USE_X_MIN #if (digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(X_MIN_PIN); #else @@ -136,7 +135,7 @@ void setup_endstop_interrupts() { pciSetup(X_MIN_PIN); #endif #endif - #if HAS_Y_MAX + #if USE_Y_MAX #if (digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y_MAX_PIN); #else @@ -144,7 +143,7 @@ void setup_endstop_interrupts() { pciSetup(Y_MAX_PIN); #endif #endif - #if HAS_Y_MIN + #if USE_Y_MIN #if (digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y_MIN_PIN); #else @@ -152,7 +151,7 @@ void setup_endstop_interrupts() { pciSetup(Y_MIN_PIN); #endif #endif - #if HAS_Z_MAX + #if USE_Z_MAX #if (digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z_MAX_PIN); #else @@ -160,7 +159,7 @@ void setup_endstop_interrupts() { pciSetup(Z_MAX_PIN); #endif #endif - #if HAS_Z_MIN + #if USE_Z_MIN #if (digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z_MIN_PIN); #else @@ -168,97 +167,97 @@ void setup_endstop_interrupts() { pciSetup(Z_MIN_PIN); #endif #endif - #if HAS_I_MAX + #if USE_I_MAX #if (digitalPinToInterrupt(I_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(I_MAX_PIN); #else - static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(I_MAX_PIN); #endif - #elif HAS_I_MIN + #elif USE_I_MIN #if (digitalPinToInterrupt(I_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(I_MIN_PIN); #else - static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(I_MIN_PIN); #endif #endif - #if HAS_J_MAX + #if USE_J_MAX #if (digitalPinToInterrupt(J_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(J_MAX_PIN); #else - static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(J_MAX_PIN); #endif - #elif HAS_J_MIN + #elif USE_J_MIN #if (digitalPinToInterrupt(J_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(J_MIN_PIN); #else - static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(J_MIN_PIN); #endif #endif - #if HAS_K_MAX + #if USE_K_MAX #if (digitalPinToInterrupt(K_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(K_MAX_PIN); #else - static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(K_MAX_PIN); #endif - #elif HAS_K_MIN + #elif USE_K_MIN #if (digitalPinToInterrupt(K_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(K_MIN_PIN); #else - static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(K_MIN_PIN); #endif #endif - #if HAS_U_MAX + #if USE_U_MAX #if (digitalPinToInterrupt(U_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(U_MAX_PIN); #else - static_assert(digitalPinHasPCICR(U_MAX_PIN), "U_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(U_MAX_PIN), "U_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(U_MAX_PIN); #endif - #elif HAS_U_MIN + #elif USE_U_MIN #if (digitalPinToInterrupt(U_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(U_MIN_PIN); #else - static_assert(digitalPinHasPCICR(U_MIN_PIN), "U_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(U_MIN_PIN), "U_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(U_MIN_PIN); #endif #endif - #if HAS_V_MAX + #if USE_V_MAX #if (digitalPinToInterrupt(V_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(V_MAX_PIN); #else - static_assert(digitalPinHasPCICR(V_MAX_PIN), "V_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(V_MAX_PIN), "V_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(V_MAX_PIN); #endif - #elif HAS_V_MIN + #elif USE_V_MIN #if (digitalPinToInterrupt(V_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(V_MIN_PIN); #else - static_assert(digitalPinHasPCICR(V_MIN_PIN), "V_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(V_MIN_PIN), "V_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(V_MIN_PIN); #endif #endif - #if HAS_W_MAX + #if USE_W_MAX #if (digitalPinToInterrupt(W_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(W_MAX_PIN); #else - static_assert(digitalPinHasPCICR(W_MAX_PIN), "W_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(W_MAX_PIN), "W_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(W_MAX_PIN); #endif - #elif HAS_W_MIN + #elif USE_W_MIN #if (digitalPinToInterrupt(W_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(W_MIN_PIN); #else - static_assert(digitalPinHasPCICR(W_MIN_PIN), "W_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(W_MIN_PIN), "W_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(W_MIN_PIN); #endif #endif - #if HAS_X2_MAX + #if USE_X2_MAX #if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(X2_MAX_PIN); #else @@ -266,7 +265,7 @@ void setup_endstop_interrupts() { pciSetup(X2_MAX_PIN); #endif #endif - #if HAS_X2_MIN + #if USE_X2_MIN #if (digitalPinToInterrupt(X2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(X2_MIN_PIN); #else @@ -274,7 +273,7 @@ void setup_endstop_interrupts() { pciSetup(X2_MIN_PIN); #endif #endif - #if HAS_Y2_MAX + #if USE_Y2_MAX #if (digitalPinToInterrupt(Y2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y2_MAX_PIN); #else @@ -282,7 +281,7 @@ void setup_endstop_interrupts() { pciSetup(Y2_MAX_PIN); #endif #endif - #if HAS_Y2_MIN + #if USE_Y2_MIN #if (digitalPinToInterrupt(Y2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y2_MIN_PIN); #else @@ -290,7 +289,7 @@ void setup_endstop_interrupts() { pciSetup(Y2_MIN_PIN); #endif #endif - #if HAS_Z2_MAX + #if USE_Z2_MAX #if (digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z2_MAX_PIN); #else @@ -298,7 +297,7 @@ void setup_endstop_interrupts() { pciSetup(Z2_MAX_PIN); #endif #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN #if (digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z2_MIN_PIN); #else @@ -306,7 +305,7 @@ void setup_endstop_interrupts() { pciSetup(Z2_MIN_PIN); #endif #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX #if (digitalPinToInterrupt(Z3_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z3_MAX_PIN); #else @@ -314,7 +313,7 @@ void setup_endstop_interrupts() { pciSetup(Z3_MAX_PIN); #endif #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN #if (digitalPinToInterrupt(Z3_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z3_MIN_PIN); #else @@ -322,7 +321,7 @@ void setup_endstop_interrupts() { pciSetup(Z3_MIN_PIN); #endif #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX #if (digitalPinToInterrupt(Z4_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z4_MAX_PIN); #else @@ -330,7 +329,7 @@ void setup_endstop_interrupts() { pciSetup(Z4_MAX_PIN); #endif #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN #if (digitalPinToInterrupt(Z4_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z4_MIN_PIN); #else @@ -338,7 +337,7 @@ void setup_endstop_interrupts() { pciSetup(Z4_MIN_PIN); #endif #endif - #if HAS_Z_MIN_PROBE_PIN + #if USE_Z_MIN_PROBE #if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z_MIN_PROBE_PIN); #else @@ -346,6 +345,14 @@ void setup_endstop_interrupts() { pciSetup(Z_MIN_PROBE_PIN); #endif #endif + #if USE_CALIBRATION + #if (digitalPinToInterrupt(CALIBRATION_PIN) != NOT_AN_INTERRUPT) + _ATTACH(CALIBRATION_PIN); + #else + static_assert(digitalPinHasPCICR(CALIBRATION_PIN), "CALIBRATION_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); + pciSetup(CALIBRATION_PIN); + #endif + #endif // If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI. } diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 0a384172c3..936f9e5688 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -23,6 +23,10 @@ #include "../../inc/MarlinConfig.h" +//#define DEBUG_AVR_FAST_PWM +#define DEBUG_OUT ENABLED(DEBUG_AVR_FAST_PWM) +#include "../../core/debug_out.h" + struct Timer { volatile uint8_t* TCCRnQ[3]; // max 3 TCCR registers per timer volatile uint16_t* OCRnQ[3]; // max 3 OCR registers per timer @@ -108,12 +112,15 @@ const Timer get_pwm_timer(const pin_t pin) { } void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { + DEBUG_ECHOLNPGM("set_pwm_frequency(pin=", pin, ", freq=", f_desired, ")"); const Timer timer = get_pwm_timer(pin); if (timer.isProtected || !timer.isPWM) return; // Don't proceed if protected timer or not recognized const bool is_timer2 = timer.n == 2; const uint16_t maxtop = is_timer2 ? 0xFF : 0xFFFF; + DEBUG_ECHOLNPGM("maxtop=", maxtop); + uint16_t res = 0xFF; // resolution (TOP value) uint8_t j = CS_NONE; // prescaler index uint8_t wgm = WGM_PWM_PC_8; // waveform generation mode @@ -121,23 +128,29 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { // Calculating the prescaler and resolution to use to achieve closest frequency if (f_desired != 0) { constexpr uint16_t prescaler[] = { 1, 8, (32), 64, (128), 256, 1024 }; // (*) are Timer 2 only - uint16_t f = (F_CPU) / (2 * 1024 * maxtop) + 1; // Start with the lowest non-zero frequency achievable (1 or 31) + uint16_t f = (F_CPU) / (uint32_t(maxtop) << 11) + 1; // Start with the lowest non-zero frequency achievable (for 16MHz, 1 or 31) - LOOP_L_N(i, COUNT(prescaler)) { // Loop through all prescaler values - const uint16_t p = prescaler[i]; + DEBUG_ECHOLNPGM("f=", f); + DEBUG_ECHOLNPGM("(prescaler loop)"); + for (uint8_t i = 0; i < COUNT(prescaler); ++i) { // Loop through all prescaler values + const uint32_t p = prescaler[i]; // Extend to 32 bits for calculations + DEBUG_ECHOLNPGM("prescaler[", i, "]=", p); uint16_t res_fast_temp, res_pc_temp; if (is_timer2) { #if ENABLED(USE_OCR2A_AS_TOP) // No resolution calculation for TIMER2 unless enabled USE_OCR2A_AS_TOP const uint16_t rft = (F_CPU) / (p * f_desired); res_fast_temp = rft - 1; res_pc_temp = rft / 2; + DEBUG_ECHOLNPGM("(Timer2) res_fast_temp=", res_fast_temp, " res_pc_temp=", res_pc_temp); #else res_fast_temp = res_pc_temp = maxtop; + DEBUG_ECHOLNPGM("(Timer2) res_fast_temp=", maxtop, " res_pc_temp=", maxtop); #endif } else { if (p == 32 || p == 128) continue; // Skip TIMER2 specific prescalers when not TIMER2 const uint16_t rft = (F_CPU) / (p * f_desired); + DEBUG_ECHOLNPGM("(Not Timer 2) F_CPU=", STRINGIFY(F_CPU), " prescaler=", p, " f_desired=", f_desired); res_fast_temp = rft - 1; res_pc_temp = rft / 2; } @@ -146,24 +159,28 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { LIMIT(res_pc_temp, 1U, maxtop); // Calculate frequencies of test prescaler and resolution values - const uint32_t f_diff = _MAX(f, f_desired) - _MIN(f, f_desired), - f_fast_temp = (F_CPU) / (p * (1 + res_fast_temp)), + const uint16_t f_fast_temp = (F_CPU) / (p * (1 + res_fast_temp)), + f_pc_temp = (F_CPU) / ((p * res_pc_temp) << 1), + f_diff = _MAX(f, f_desired) - _MIN(f, f_desired), f_fast_diff = _MAX(f_fast_temp, f_desired) - _MIN(f_fast_temp, f_desired), - f_pc_temp = (F_CPU) / (2 * p * res_pc_temp), f_pc_diff = _MAX(f_pc_temp, f_desired) - _MIN(f_pc_temp, f_desired); + DEBUG_ECHOLNPGM("f_fast_temp=", f_fast_temp, " f_pc_temp=", f_pc_temp, " f_diff=", f_diff, " f_fast_diff=", f_fast_diff, " f_pc_diff=", f_pc_diff); + if (f_fast_diff < f_diff && f_fast_diff <= f_pc_diff) { // FAST values are closest to desired f // Set the Wave Generation Mode to FAST PWM wgm = is_timer2 ? uint8_t(TERN(USE_OCR2A_AS_TOP, WGM2_FAST_PWM_OCR2A, WGM2_FAST_PWM)) : uint8_t(WGM_FAST_PWM_ICRn); // Remember this combination f = f_fast_temp; res = res_fast_temp; j = i + 1; + DEBUG_ECHOLNPGM("(FAST) updated f=", f); } else if (f_pc_diff < f_diff) { // PHASE CORRECT values are closes to desired f // Set the Wave Generation Mode to PWM PHASE CORRECT wgm = is_timer2 ? uint8_t(TERN(USE_OCR2A_AS_TOP, WGM2_PWM_PC_OCR2A, WGM2_PWM_PC)) : uint8_t(WGM_PWM_PC_ICRn); f = f_pc_temp; res = res_pc_temp; j = i + 1; + DEBUG_ECHOLNPGM("(PHASE) updated f=", f); } - } + } // prescaler loop } _SET_WGMnQ(timer, wgm); @@ -215,7 +232,7 @@ void MarlinHAL::init_pwm_timers() { #endif }; - LOOP_L_N(i, COUNT(pwm_pin)) + for (uint8_t i = 0; i < COUNT(pwm_pin); ++i) set_pwm_frequency(pwm_pin[i], 1000); } diff --git a/Marlin/src/HAL/AVR/fastio.cpp b/Marlin/src/HAL/AVR/fastio.cpp index 5c6ef18915..98fd636ebf 100644 --- a/Marlin/src/HAL/AVR/fastio.cpp +++ b/Marlin/src/HAL/AVR/fastio.cpp @@ -241,7 +241,7 @@ uint8_t extDigitalRead(const int8_t pin) { * * DC values -1.0 to 1.0. Negative duty cycle inverts the pulse. */ -uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb, const float dcc) { +uint16_t set_pwm_frequency_hz(const float hz, const float dca, const float dcb, const float dcc) { float count = 0; if (hz > 0 && (dca || dcb || dcc)) { count = float(F_CPU) / hz; // 1x prescaler, TOP for 16MHz base freq. @@ -254,7 +254,7 @@ uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb else { prescaler = 1; SET_CS(5, PRESCALER_1); } count /= float(prescaler); - const float pwm_top = round(count); // Get the rounded count + const float pwm_top = roundf(count); // Get the rounded count ICR5 = (uint16_t)pwm_top - 1; // Subtract 1 for TOP OCR5A = pwm_top * ABS(dca); // Update and scale DCs @@ -280,7 +280,7 @@ uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb SET_CS(5, PRESCALER_64); // 16MHz / 64 = 250kHz OCR5A = OCR5B = OCR5C = 0; } - return round(count); + return roundf(count); } #endif diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index 51d3b311ee..4516d9cd54 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -255,84 +255,6 @@ enum ClockSource2 : uint8_t { #define SET_FOCB(T,V) SET_FOC(T,B,V) #define SET_FOCC(T,V) SET_FOC(T,C,V) -#if 0 - -/** - * PWM availability macros - */ - -// Determine which hardware PWMs are already in use -#define _PWM_CHK_FAN_B(P) (P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == E6_AUTO_FAN_PIN || P == E7_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN || P == COOLER_AUTO_FAN_PIN) -#if PIN_EXISTS(CONTROLLER_FAN) - #define PWM_CHK_FAN_B(P) (_PWM_CHK_FAN_B(P) || P == CONTROLLER_FAN_PIN) -#else - #define PWM_CHK_FAN_B(P) _PWM_CHK_FAN_B(P) -#endif - -#if ANY_PIN(FAN, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7) - #if PIN_EXISTS(FAN7) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN || P == FAN6_PIN || P == FAN7_PIN) - #elif PIN_EXISTS(FAN6) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN || P == FAN6_PIN) - #elif PIN_EXISTS(FAN5) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN) - #elif PIN_EXISTS(FAN4) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN) - #elif PIN_EXISTS(FAN3) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN) - #elif PIN_EXISTS(FAN2) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN) - #elif PIN_EXISTS(FAN1) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN) - #else - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN) - #endif -#else - #define PWM_CHK_FAN_A(P) false -#endif - -#if HAS_MOTOR_CURRENT_PWM - #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_Z || P == MOTOR_CURRENT_PWM_XY) - #elif PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_Z) - #else - #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E) - #endif -#else - #define PWM_CHK_MOTOR_CURRENT(P) false -#endif - -#ifdef NUM_SERVOS - #if AVR_ATmega2560_FAMILY - #define PWM_CHK_SERVO(P) (P == 5 || (NUM_SERVOS > 12 && P == 6) || (NUM_SERVOS > 24 && P == 46)) // PWMS 3A, 4A & 5A - #elif AVR_ATmega2561_FAMILY - #define PWM_CHK_SERVO(P) (P == 5) // PWM3A - #elif AVR_ATmega1284_FAMILY - #define PWM_CHK_SERVO(P) false - #elif AVR_AT90USB1286_FAMILY - #define PWM_CHK_SERVO(P) (P == 16) // PWM3A - #elif AVR_ATmega328_FAMILY - #define PWM_CHK_SERVO(P) false - #endif -#else - #define PWM_CHK_SERVO(P) false -#endif - -#if ENABLED(BARICUDA) - #if HAS_HEATER_1 && HAS_HEATER_2 - #define PWM_CHK_HEATER(P) (P == HEATER_1_PIN || P == HEATER_2_PIN) - #elif HAS_HEATER_1 - #define PWM_CHK_HEATER(P) (P == HEATER_1_PIN) - #endif -#else - #define PWM_CHK_HEATER(P) false -#endif - -#define PWM_CHK(P) (PWM_CHK_HEATER(P) || PWM_CHK_SERVO(P) || PWM_CHK_MOTOR_CURRENT(P) || PWM_CHK_FAN_A(P) || PWM_CHK_FAN_B(P)) - -#endif // PWM_CHK is not used in Marlin - // define which hardware PWMs are available for the current CPU // all timer 1 PWMS deleted from this list because they are never available #if AVR_ATmega2560_FAMILY diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1280.h b/Marlin/src/HAL/AVR/fastio/fastio_1280.h index f482f823e8..57d6181d2e 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1280.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1280.h @@ -27,43 +27,41 @@ * Hardware Pin : 02 03 06 07 01 05 15 16 17 18 23 24 25 26 64 63 13 12 46 45 44 43 78 77 76 75 74 73 72 71 60 59 58 57 56 55 54 53 50 70 52 51 42 41 40 39 38 37 36 35 22 21 20 19 97 96 95 94 93 92 91 90 89 88 87 86 85 84 83 82 | 04 08 09 10 11 14 27 28 29 30 31 32 33 34 47 48 49 61 62 65 66 67 68 69 79 80 81 98 99 100 * Port : E0 E1 E4 E5 G5 E3 H3 H4 H5 H6 B4 B5 B6 B7 J1 J0 H1 H0 D3 D2 D1 D0 A0 A1 A2 A3 A4 A5 A6 A7 C7 C6 C5 C4 C3 C2 C1 C0 D7 G2 G1 G0 L7 L6 L5 L4 L3 L2 L1 L0 B3 B2 B1 B0 F0 F1 F2 F3 F4 F5 F6 F7 K0 K1 K2 K3 K4 K5 K6 K7 | E2 E6 E7 xx xx H2 H7 G3 G4 xx xx xx xx xx D4 D5 D6 xx xx J2 J3 J4 J5 J6 J7 xx xx xx xx xx * Logical Pin : 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 | 78 79 80 xx xx 84 85 71 70 xx xx xx xx xx 81 82 83 xx xx 72 73 75 76 77 74 xx xx xx xx xx + * Analog Input : 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 */ #include "../fastio.h" -// change for your board -#define DEBUG_LED DIO21 - // UART -#define RXD DIO0 -#define TXD DIO1 +#define RXD 0 +#define TXD 1 // SPI -#define SCK DIO52 -#define MISO DIO50 -#define MOSI DIO51 -#define SS DIO53 +#define MISO 50 +#define MOSI 51 +#define SCK 52 +#define SS 53 // TWI (I2C) -#define SCL DIO21 -#define SDA DIO20 +#define SCL 21 +#define SDA 20 // Timers and PWM -#define OC0A DIO13 -#define OC0B DIO4 -#define OC1A DIO11 -#define OC1B DIO12 -#define OC2A DIO10 -#define OC2B DIO9 -#define OC3A DIO5 -#define OC3B DIO2 -#define OC3C DIO3 -#define OC4A DIO6 -#define OC4B DIO7 -#define OC4C DIO8 -#define OC5A DIO46 -#define OC5B DIO45 -#define OC5C DIO44 +#define OC0A 13 +#define OC0B 4 +#define OC1A 11 +#define OC1B 12 +#define OC2A 10 +#define OC2B 9 +#define OC3A 5 +#define OC3B 2 +#define OC3C 3 +#define OC4A 6 +#define OC4B 7 +#define OC4C 8 +#define OC5A 46 +#define OC5B 45 +#define OC5C 44 // Digital I/O diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1281.h b/Marlin/src/HAL/AVR/fastio/fastio_1281.h index e0bc5e2995..fdff219ec3 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1281.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1281.h @@ -30,32 +30,29 @@ #include "../fastio.h" -// change for your board -#define DEBUG_LED DIO46 - // UART -#define RXD DIO0 -#define TXD DIO1 +#define RXD 0 +#define TXD 1 // SPI -#define SCK DIO10 -#define MISO DIO12 -#define MOSI DIO11 -#define SS DIO16 +#define SCK 10 +#define MISO 12 +#define MOSI 11 +#define SS 16 // TWI (I2C) -#define SCL DIO17 -#define SDA DIO18 +#define SCL 17 +#define SDA 18 // Timers and PWM -#define OC0A DIO9 -#define OC0B DIO4 -#define OC1A DIO7 -#define OC1B DIO8 -#define OC2A DIO6 -#define OC3A DIO5 -#define OC3B DIO2 -#define OC3C DIO3 +#define OC0A 9 +#define OC0B 4 +#define OC1A 7 +#define OC1B 8 +#define OC2A 6 +#define OC3A 5 +#define OC3B 2 +#define OC3C 3 // Digital I/O diff --git a/Marlin/src/HAL/AVR/fastio/fastio_168.h b/Marlin/src/HAL/AVR/fastio/fastio_168.h index 8cfdd1e8f8..36dc552385 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_168.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_168.h @@ -30,29 +30,27 @@ #include "../fastio.h" -#define DEBUG_LED AIO5 - // UART -#define RXD DIO0 -#define TXD DIO1 +#define RXD 0 +#define TXD 1 // SPI -#define SCK DIO13 -#define MISO DIO12 -#define MOSI DIO11 -#define SS DIO10 +#define SS 10 +#define MOSI 11 +#define MISO 12 +#define SCK 13 // TWI (I2C) #define SCL AIO5 #define SDA AIO4 // Timers and PWM -#define OC0A DIO6 -#define OC0B DIO5 -#define OC1A DIO9 -#define OC1B DIO10 -#define OC2A DIO11 -#define OC2B DIO3 +#define OC0A 6 +#define OC0B 5 +#define OC1A 9 +#define OC1B 10 +#define OC2A 11 +#define OC2B 3 // Digital I/O diff --git a/Marlin/src/HAL/AVR/fastio/fastio_644.h b/Marlin/src/HAL/AVR/fastio/fastio_644.h index f4a9427e0a..e20a3d345e 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_644.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_644.h @@ -56,34 +56,32 @@ #include "../fastio.h" -#define DEBUG_LED DIO0 - // UART -#define RXD DIO8 -#define TXD DIO9 -#define RXD0 DIO8 -#define TXD0 DIO9 +#define RXD 8 +#define TXD 9 +#define RXD0 8 +#define TXD0 9 -#define RXD1 DIO10 -#define TXD1 DIO11 +#define RXD1 10 +#define TXD1 11 // SPI -#define SCK DIO7 -#define MISO DIO6 -#define MOSI DIO5 -#define SS DIO4 +#define SS 4 +#define MOSI 5 +#define MISO 6 +#define SCK 7 // TWI (I2C) -#define SCL DIO16 -#define SDA DIO17 +#define SCL 16 +#define SDA 17 // Timers and PWM -#define OC0A DIO3 -#define OC0B DIO4 -#define OC1A DIO13 -#define OC1B DIO12 -#define OC2A DIO15 -#define OC2B DIO14 +#define OC0A 3 +#define OC0B 4 +#define OC1A 13 +#define OC1B 12 +#define OC2A 15 +#define OC2B 14 // Digital I/O diff --git a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h index 51d400b705..a9af519ff3 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h @@ -26,19 +26,16 @@ * * Logical Pin: 28 29 30 31 32 33 34 35 20 21 22 23 24 25 26 27 10 11 12 13 14 15 16 17 00 01 02 03 04 05 06 07 08 09(46*47)36 37 18 19 38 39 40 41 42 43 44 45 * Port: A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 - * The logical pins 46 and 47 are not supported by Teensyduino, but are supported below as E2 and E3 + * Logical pins 46-47 aren't supported by Teensyduino, but are supported below as E2 and E3 */ #include "../fastio.h" -// change for your board -#define DEBUG_LED DIO31 /* led D5 red */ - // SPI -#define SCK DIO21 // 9 -#define MISO DIO23 // 11 -#define MOSI DIO22 // 10 -#define SS DIO20 // 8 +#define SS 20 // 8 +#define SCK 21 // 9 +#define MOSI 22 // 10 +#define MISO 23 // 11 // Digital I/O @@ -366,8 +363,11 @@ #define AIO7_PWM 0 #define AIO7_DDR DDRF -//-- Begin not supported by Teensyduino -//-- don't use Arduino functions on these pins pinMode/digitalWrite/etc +//-- 46-47 are not supported by Teensyduino +//-- Don't use Arduino functions (pinMode, digitalWrite, etc.) on these pins +#define PIN_E2 46 +#define PIN_E3 47 + #define DIO46_PIN PINE2 #define DIO46_RPORT PINE #define DIO46_WPORT PORTE @@ -380,10 +380,7 @@ #define DIO47_PWM 0 #define DIO47_DDR DDRE -#define TEENSY_E2 46 -#define TEENSY_E3 47 - -//-- end not supported by Teensyduino +//-- #undef PA0 #define PA0_PIN PINA0 @@ -679,7 +676,6 @@ #define PF7_PWM 0 #define PF7_DDR DDRF - /** * Some of the pin mapping functions of the Teensduino extension to the Arduino IDE * do not function the same as the other Arduino extensions. diff --git a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h index a611ccd7c4..65b019b261 100644 --- a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/AVR." +#ifndef SERIAL_PORT + #define SERIAL_PORT 0 #endif diff --git a/Marlin/src/HAL/AVR/inc/Conditionals_type.h b/Marlin/src/HAL/AVR/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/AVR/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 89425ca853..08fe21d4f8 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -25,34 +25,40 @@ * Test AVR-specific configuration values for errors at compile-time. */ +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for HAL/AVR." +#endif + /** * Check for common serial pin conflicts */ #define CHECK_SERIAL_PIN(N) ( \ - X_STOP_PIN == N || Y_STOP_PIN == N || Z_STOP_PIN == N \ - || X_MIN_PIN == N || Y_MIN_PIN == N || Z_MIN_PIN == N \ - || X_MAX_PIN == N || Y_MAX_PIN == N || Z_MAX_PIN == N \ - || X_STEP_PIN == N || Y_STEP_PIN == N || Z_STEP_PIN == N \ - || X_DIR_PIN == N || Y_DIR_PIN == N || Z_DIR_PIN == N \ - || X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \ - || BTN_EN1 == N || BTN_EN2 == N \ + X_STOP_PIN == N || Y_STOP_PIN == N || Z_STOP_PIN == N \ + || X_MIN_PIN == N || Y_MIN_PIN == N || Z_MIN_PIN == N \ + || X_MAX_PIN == N || Y_MAX_PIN == N || Z_MAX_PIN == N \ + || X_STEP_PIN == N || Y_STEP_PIN == N || Z_STEP_PIN == N \ + || X_DIR_PIN == N || Y_DIR_PIN == N || Z_DIR_PIN == N \ + || X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \ + || BTN_EN1 == N || BTN_EN2 == N || LCD_PINS_EN == N \ ) -#if CONF_SERIAL_IS(0) +#if SERIAL_IN_USE(0) // D0-D1. No known conflicts. #endif -#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) - #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 -#else - #if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(10) || CHECK_SERIAL_PIN(11)) - #error "Serial Port 1 pin D10 and/or D11 conflicts with another pin on the board." +#if SERIAL_IN_USE(1) + #if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) + #if 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 + #else + #if CHECK_SERIAL_PIN(10) || CHECK_SERIAL_PIN(11) + #error "Serial Port 1 pin D10 and/or D11 conflicts with another pin on the board." + #endif #endif #endif -#if CONF_SERIAL_IS(2) && (CHECK_SERIAL_PIN(16) || CHECK_SERIAL_PIN(17)) +#if SERIAL_IN_USE(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)) +#if SERIAL_IN_USE(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 @@ -67,8 +73,8 @@ /** * Checks for SOFT PWM */ -#if HAS_FAN0 && FAN_PIN == 9 && DISABLED(FAN_SOFT_PWM) && ENABLED(SPEAKER) - #error "FAN_PIN 9 Hardware PWM uses Timer 2 which conflicts with Arduino AVR Tone Timer (for SPEAKER)." +#if HAS_FAN0 && FAN0_PIN == 9 && DISABLED(FAN_SOFT_PWM) && ENABLED(SPEAKER) + #error "FAN0_PIN 9 Hardware PWM uses Timer 2 which conflicts with Arduino AVR Tone Timer (for SPEAKER)." #error "Disable SPEAKER or enable FAN_SOFT_PWM." #endif @@ -89,11 +95,11 @@ /** * The Trinamic library includes SoftwareSerial.h, leading to a compile error. */ -#if BOTH(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE) +#if ALL(HAS_TMC_SW_SERIAL, ENDSTOP_INTERRUPTS_FEATURE) #error "TMCStepper includes SoftwareSerial.h which is incompatible with ENDSTOP_INTERRUPTS_FEATURE. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif -#if BOTH(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS) +#if ALL(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS) #error "MONITOR_DRIVER_STATUS causes performance issues when used with SoftwareSerial-connected drivers. Disable MONITOR_DRIVER_STATUS or use hardware serial to continue." #endif diff --git a/Marlin/src/HAL/AVR/math.h b/Marlin/src/HAL/AVR/math.h index 7dd1018ff1..16848524fa 100644 --- a/Marlin/src/HAL/AVR/math.h +++ b/Marlin/src/HAL/AVR/math.h @@ -27,13 +27,14 @@ // intRes = longIn1 * longIn2 >> 24 // uses: -// A[tmp] to store 0 -// B[tmp] to store bits 16-23 of the 48bit result. The top bit is used to round the two byte result. -// note that the lower two bytes and the upper byte of the 48bit result are not calculated. -// this can cause the result to be out by one as the lower bytes may cause carries into the upper ones. -// B A are bits 24-39 and are the returned value -// C B A is longIn1 -// D C B A is longIn2 +// r1, r0 for the result of mul. +// [tmp1] to store 0. +// [tmp2] to store bits 16-23 of the 56 bit result. The top bit of [tmp2] is used for rounding. +// Note that the lower two bytes and the upper two bytes of the 56 bit result are not calculated. +// This can cause the result to be out by one as the lower bytes may cause carries into the upper ones. +// [intRes] (A B) is bits 24-39 and is the returned value. +// [longIn1] (C B A) is a 24 bit parameter. +// [longIn2] (D C B A) is a 32 bit parameter. // FORCE_INLINE static uint16_t MultiU24X32toH16(uint32_t longIn1, uint32_t longIn2) { uint8_t tmp1; @@ -66,11 +67,9 @@ FORCE_INLINE static uint16_t MultiU24X32toH16(uint32_t longIn1, uint32_t longIn2 A("add %[tmp2], r1") A("adc %A[intRes], %[tmp1]") A("adc %B[intRes], %[tmp1]") - A("lsr %[tmp2]") - A("adc %A[intRes], %[tmp1]") - A("adc %B[intRes], %[tmp1]") A("mul %D[longIn2], %A[longIn1]") - A("add %A[intRes], r0") + A("lsl %[tmp2]") + A("adc %A[intRes], r0") A("adc %B[intRes], r1") A("mul %D[longIn2], %B[longIn1]") A("add %B[intRes], r0") @@ -85,29 +84,26 @@ FORCE_INLINE static uint16_t MultiU24X32toH16(uint32_t longIn1, uint32_t longIn2 return intRes; } -// intRes = intIn1 * intIn2 >> 16 +// charRes = charIn1 * charIn2 >> 8 // uses: -// r26 to store 0 -// r27 to store the byte 1 of the 24 bit result -FORCE_INLINE static uint16_t MultiU16X8toH16(uint8_t charIn1, uint16_t intIn2) { - uint8_t tmp; - uint16_t intRes; +// r1, r0 for the result of mul. After the mul, r0 holds bits 0-7 of the 16 bit result, +// and the top bit of r0 is used for rounding. +// [charRes] is bits 8-15 and is the returned value. +// [charIn1] is an 8 bit parameter. +// [charIn2] is an 8 bit parameter. +// +FORCE_INLINE static uint8_t MultiU8X8toH8(uint8_t charIn1, uint8_t charIn2) { + uint8_t charRes; __asm__ __volatile__ ( - A("clr %[tmp]") - A("mul %[charIn1], %B[intIn2]") - A("movw %A[intRes], r0") - A("mul %[charIn1], %A[intIn2]") - A("add %A[intRes], r1") - A("adc %B[intRes], %[tmp]") - A("lsr r0") - A("adc %A[intRes], %[tmp]") - A("adc %B[intRes], %[tmp]") + A("mul %[charIn1], %[charIn2]") + A("mov %[charRes], r1") A("clr r1") - : [intRes] "=&r" (intRes), - [tmp] "=&r" (tmp) + A("lsl r0") + A("adc %[charRes], r1") + : [charRes] "=&r" (charRes) : [charIn1] "d" (charIn1), - [intIn2] "d" (intIn2) + [charIn2] "d" (charIn2) : "cc" ); - return intRes; + return charRes; } diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index dab4e44715..c833964a29 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -22,7 +22,23 @@ #pragma once /** - * PWM print routines for Atmel 8 bit AVR CPUs + * Pins Debugging for Atmel 8 bit AVR CPUs + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) */ #include "../../inc/MarlinConfig.h" @@ -39,55 +55,56 @@ #include "pinsDebug_Teensyduino.h" // Can't use the "digitalPinToPort" function from the Teensyduino type IDEs // portModeRegister takes a different argument - #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p) - #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p) - #define digitalPinToPort_DEBUG(p) digitalPinToPort(p) - #define GET_PINMODE(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin)) + #define digitalPinToTimer_DEBUG(P) digitalPinToTimer(P) + #define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask(P) + #define digitalPinToPort_DEBUG(P) digitalPinToPort(P) + #define getValidPinMode(P) (*portModeRegister(P) & digitalPinToBitMask_DEBUG(P)) #elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70 #include "pinsDebug_plus_70.h" - #define digitalPinToTimer_DEBUG(p) digitalPinToTimer_plus_70(p) - #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask_plus_70(p) - #define digitalPinToPort_DEBUG(p) digitalPinToPort_plus_70(p) - bool GET_PINMODE(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); } + #define digitalPinToTimer_DEBUG(P) digitalPinToTimer_plus_70(P) + #define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask_plus_70(P) + #define digitalPinToPort_DEBUG(P) digitalPinToPort_plus_70(P) + bool getValidPinMode(pin_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); } #else - #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p) - #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p) - #define digitalPinToPort_DEBUG(p) digitalPinToPort(p) - bool GET_PINMODE(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); } - #define GET_ARRAY_PIN(p) pgm_read_byte(&pin_array[p].pin) + #define digitalPinToTimer_DEBUG(P) digitalPinToTimer(P) + #define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask(P) + #define digitalPinToPort_DEBUG(P) digitalPinToPort(P) + bool getValidPinMode(pin_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); } + #define getPinByIndex(x) pgm_read_byte(&pin_array[x].pin) #endif -#define VALID_PIN(pin) (pin >= 0 && pin < NUM_DIGITAL_PINS ? 1 : 0) +#define isValidPin(P) (P >= 0 && P < NUMBER_PINS_TOTAL) #if AVR_ATmega1284_FAMILY - #define DIGITAL_PIN_TO_ANALOG_PIN(P) int(analogInputToDigitalPin(0) - (P)) - #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(7) && (P) <= analogInputToDigitalPin(0)) + #define isAnalogPin(P) WITHIN(P, analogInputToDigitalPin(7), analogInputToDigitalPin(0)) + #define digitalPinToAnalogIndex(P) int(isAnalogPin(P) ? (P) - analogInputToDigitalPin(7) : -1) #else - #define DIGITAL_PIN_TO_ANALOG_PIN(P) int((P) - analogInputToDigitalPin(0)) - #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && ((P) <= analogInputToDigitalPin(15) || (P) <= analogInputToDigitalPin(7))) + #define _ANALOG1(P) WITHIN(P, analogInputToDigitalPin(0), analogInputToDigitalPin(7)) + #define _ANALOG2(P) WITHIN(P, analogInputToDigitalPin(8), analogInputToDigitalPin(15)) + #define isAnalogPin(P) (_ANALOG1(P) || _ANALOG2(P)) + #define digitalPinToAnalogIndex(P) int(_ANALOG1(P) ? (P) - analogInputToDigitalPin(0) : _ANALOG2(P) ? (P) - analogInputToDigitalPin(8) + 8 : -1) #endif -#define GET_ARRAY_PIN(p) pgm_read_byte(&pin_array[p].pin) +#define getPinByIndex(x) pgm_read_byte(&pin_array[x].pin) #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) { - PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name); - LOOP_L_N(y, MAX_NAME_LENGTH) { +void printPinNameByIndex(const uint8_t index) { + PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[index].name); + for (uint8_t y = 0; y < MAX_NAME_LENGTH; ++y) { char temp_char = pgm_read_byte(name_mem_pointer + y); if (temp_char != 0) SERIAL_CHAR(temp_char); else { - LOOP_L_N(i, MAX_NAME_LENGTH - y) SERIAL_CHAR(' '); + for (uint8_t i = 0; i < MAX_NAME_LENGTH - y; ++i) SERIAL_CHAR(' '); break; } } } -#define GET_ARRAY_IS_DIGITAL(x) pgm_read_byte(&pin_array[x].is_digital) - +#define getPinIsDigitalByIndex(x) pgm_read_byte(&pin_array[x].is_digital) #if defined(__AVR_ATmega1284P__) // 1284 IDE extensions set this to the number of #undef NUM_DIGITAL_PINS // digital only pins while all other CPUs have it @@ -108,7 +125,7 @@ void PRINT_ARRAY_NAME(uint8_t x) { * Print a pin's PWM status. * Return true if it's currently a PWM pin. */ -static bool pwm_status(uint8_t pin) { +bool pwm_status(const uint8_t pin) { char buffer[20]; // for the sprintf statements switch (digitalPinToTimer_DEBUG(pin)) { @@ -162,7 +179,6 @@ static bool pwm_status(uint8_t pin) { SERIAL_ECHO_SP(2); } // pwm_status - const volatile uint8_t* const PWM_other[][3] PROGMEM = { { &TCCR0A, &TCCR0B, &TIMSK0 }, { &TCCR1A, &TCCR1B, &TIMSK1 }, @@ -180,7 +196,6 @@ const volatile uint8_t* const PWM_other[][3] PROGMEM = { #endif }; - const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { #ifdef TIMER0A @@ -216,7 +231,6 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { #endif }; - #define TCCR_A(T) pgm_read_word(&PWM_other[T][0]) #define TCCR_B(T) pgm_read_word(&PWM_other[T][1]) #define TIMSK(T) pgm_read_word(&PWM_other[T][2]) @@ -231,12 +245,12 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { #define OCR_VAL(T, L) pgm_read_word(&PWM_OCR[T][L]) -static void err_is_counter() { SERIAL_ECHOPGM(" non-standard PWM mode"); } -static void err_is_interrupt() { SERIAL_ECHOPGM(" compare interrupt enabled"); } -static void err_prob_interrupt() { SERIAL_ECHOPGM(" overflow interrupt enabled"); } -static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); SERIAL_ECHO_SP(14); } +void err_is_counter() { SERIAL_ECHOPGM(" non-standard PWM mode"); } +void err_is_interrupt() { SERIAL_ECHOPGM(" compare interrupt enabled"); } +void err_prob_interrupt() { SERIAL_ECHOPGM(" overflow interrupt enabled"); } +void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); SERIAL_ECHO_SP(14); } -inline void com_print(const uint8_t N, const uint8_t Z) { +void com_print(const uint8_t N, const uint8_t Z) { const uint8_t *TCCRA = (uint8_t*)TCCR_A(N); SERIAL_ECHOPGM(" COM", AS_DIGIT(N)); SERIAL_CHAR(Z); @@ -278,7 +292,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - if (TEST(*TMSK, TOIE)) err_prob_interrupt(); } -static void pwm_details(uint8_t pin) { +void printPinPWM(const uint8_t pin) { switch (digitalPinToTimer_DEBUG(pin)) { #if ABTEST(0) @@ -349,52 +363,46 @@ static void pwm_details(uint8_t pin) { #else UNUSED(print_is_also_tied); #endif -} // pwm_details +} // printPinPWM #ifndef digitalRead_mod // Use Teensyduino's version of digitalRead - it doesn't disable the PWMs - int digitalRead_mod(const int8_t pin) { // same as digitalRead except the PWM stop section has been removed + int digitalRead_mod(const pin_t pin) { // same as digitalRead except the PWM stop section has been removed const uint8_t port = digitalPinToPort_DEBUG(pin); return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask_DEBUG(pin)) ? HIGH : LOW; } #endif -#ifndef PRINT_PORT +void printPinPort(const pin_t pin) { // print port number + #ifdef digitalPinToPort_DEBUG + uint8_t x; + SERIAL_ECHOPGM(" Port: "); + #if AVR_AT90USB1286_FAMILY + x = (pin == PIN_E2 || pin == PIN_E3) ? 'E' : 'A' + digitalPinToPort_DEBUG(pin) - 1; + #else + x = 'A' + digitalPinToPort_DEBUG(pin) - 1; + #endif + SERIAL_CHAR(x); - void print_port(int8_t pin) { // print port number - #ifdef digitalPinToPort_DEBUG - uint8_t x; - SERIAL_ECHOPGM(" Port: "); - #if AVR_AT90USB1286_FAMILY - x = (pin == 46 || pin == 47) ? 'E' : digitalPinToPort_DEBUG(pin) + 64; - #else - x = digitalPinToPort_DEBUG(pin) + 64; - #endif - SERIAL_CHAR(x); - - #if AVR_AT90USB1286_FAMILY - if (pin == 46) - x = '2'; - else if (pin == 47) - x = '3'; - else { - uint8_t temp = digitalPinToBitMask_DEBUG(pin); - for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; - } - #else + #if AVR_AT90USB1286_FAMILY + if (pin == PIN_E2) + x = '2'; + else if (pin == PIN_E3) + x = '3'; + else { uint8_t temp = digitalPinToBitMask_DEBUG(pin); for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; - #endif - SERIAL_CHAR(x); + } #else - SERIAL_ECHO_SP(10); + uint8_t temp = digitalPinToBitMask_DEBUG(pin); + for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; #endif - } + SERIAL_CHAR(x); + #else + SERIAL_ECHO_SP(10); + #endif +} - #define PRINT_PORT(p) print_port(p) - -#endif - -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) #undef ABTEST diff --git a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h index 582ae79ba7..463a77ec1d 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h +++ b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h @@ -22,11 +22,10 @@ #pragma once // -// some of the pin mapping functions of the Teensduino extension to the Arduino IDE -// do not function the same as the other Arduino extensions +// Some of the pin mapping functions of the Arduino IDE Teensduino extension +// function differently from other Arduino extensions. // - #define TEENSYDUINO_IDE //digitalPinToTimer(pin) function works like Arduino but Timers are not defined @@ -48,8 +47,6 @@ #define PE 5 #define PF 6 -#undef digitalPinToPort - const uint8_t PROGMEM digital_pin_to_port_PGM[] = { PD, // 0 - PD0 - INT0 - PWM PD, // 1 - PD1 - INT1 - PWM @@ -101,11 +98,11 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = { PE, // 47 - PE3 (not defined in teensyduino) }; -#define digitalPinToPort(P) ( pgm_read_byte( digital_pin_to_port_PGM + (P) ) ) +#define digitalPinToPort(P) pgm_read_byte(digital_pin_to_port_PGM[P]) // digitalPinToBitMask(pin) is OK -#define digitalRead_mod(p) extDigitalRead(p) // Teensyduino's version of digitalRead doesn't +#define digitalRead_mod(P) extDigitalRead(P) // Teensyduino's version of digitalRead doesn't // disable the PWMs so we can use it as is // portModeRegister(pin) is OK diff --git a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h index d9aa44c3cb..6565acd523 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h +++ b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h @@ -48,92 +48,92 @@ const uint8_t PROGMEM digital_pin_to_port_PGM_plus_70[] = { // PORTLIST // ------------------------ - PE , // PE 0 ** 0 ** USART0_RX - PE , // PE 1 ** 1 ** USART0_TX - PE , // PE 4 ** 2 ** PWM2 - PE , // PE 5 ** 3 ** PWM3 - PG , // PG 5 ** 4 ** PWM4 - PE , // PE 3 ** 5 ** PWM5 - PH , // PH 3 ** 6 ** PWM6 - PH , // PH 4 ** 7 ** PWM7 - PH , // PH 5 ** 8 ** PWM8 - PH , // PH 6 ** 9 ** PWM9 - PB , // PB 4 ** 10 ** PWM10 - PB , // PB 5 ** 11 ** PWM11 - PB , // PB 6 ** 12 ** PWM12 - PB , // PB 7 ** 13 ** PWM13 - PJ , // PJ 1 ** 14 ** USART3_TX - PJ , // PJ 0 ** 15 ** USART3_RX - PH , // PH 1 ** 16 ** USART2_TX - PH , // PH 0 ** 17 ** USART2_RX - PD , // PD 3 ** 18 ** USART1_TX - PD , // PD 2 ** 19 ** USART1_RX - PD , // PD 1 ** 20 ** I2C_SDA - PD , // PD 0 ** 21 ** I2C_SCL - PA , // PA 0 ** 22 ** D22 - PA , // PA 1 ** 23 ** D23 - PA , // PA 2 ** 24 ** D24 - PA , // PA 3 ** 25 ** D25 - PA , // PA 4 ** 26 ** D26 - PA , // PA 5 ** 27 ** D27 - PA , // PA 6 ** 28 ** D28 - PA , // PA 7 ** 29 ** D29 - PC , // PC 7 ** 30 ** D30 - PC , // PC 6 ** 31 ** D31 - PC , // PC 5 ** 32 ** D32 - PC , // PC 4 ** 33 ** D33 - PC , // PC 3 ** 34 ** D34 - PC , // PC 2 ** 35 ** D35 - PC , // PC 1 ** 36 ** D36 - PC , // PC 0 ** 37 ** D37 - PD , // PD 7 ** 38 ** D38 - PG , // PG 2 ** 39 ** D39 - PG , // PG 1 ** 40 ** D40 - PG , // PG 0 ** 41 ** D41 - PL , // PL 7 ** 42 ** D42 - PL , // PL 6 ** 43 ** D43 - PL , // PL 5 ** 44 ** D44 - PL , // PL 4 ** 45 ** D45 - PL , // PL 3 ** 46 ** D46 - PL , // PL 2 ** 47 ** D47 - PL , // PL 1 ** 48 ** D48 - PL , // PL 0 ** 49 ** D49 - PB , // PB 3 ** 50 ** SPI_MISO - PB , // PB 2 ** 51 ** SPI_MOSI - PB , // PB 1 ** 52 ** SPI_SCK - PB , // PB 0 ** 53 ** SPI_SS - PF , // PF 0 ** 54 ** A0 - PF , // PF 1 ** 55 ** A1 - PF , // PF 2 ** 56 ** A2 - PF , // PF 3 ** 57 ** A3 - PF , // PF 4 ** 58 ** A4 - PF , // PF 5 ** 59 ** A5 - PF , // PF 6 ** 60 ** A6 - PF , // PF 7 ** 61 ** A7 - PK , // PK 0 ** 62 ** A8 - PK , // PK 1 ** 63 ** A9 - PK , // PK 2 ** 64 ** A10 - PK , // PK 3 ** 65 ** A11 - PK , // PK 4 ** 66 ** A12 - PK , // PK 5 ** 67 ** A13 - PK , // PK 6 ** 68 ** A14 - PK , // PK 7 ** 69 ** A15 - PG , // PG 4 ** 70 ** - PG , // PG 3 ** 71 ** - PJ , // PJ 2 ** 72 ** - PJ , // PJ 3 ** 73 ** - PJ , // PJ 7 ** 74 ** - PJ , // PJ 4 ** 75 ** - PJ , // PJ 5 ** 76 ** - PJ , // PJ 6 ** 77 ** - PE , // PE 2 ** 78 ** - PE , // PE 6 ** 79 ** - PE , // PE 7 ** 80 ** - PD , // PD 4 ** 81 ** - PD , // PD 5 ** 82 ** - PD , // PD 6 ** 83 ** - PH , // PH 2 ** 84 ** - PH , // PH 7 ** 85 ** + PE, // PE 0 ** 0 ** USART0_RX + PE, // PE 1 ** 1 ** USART0_TX + PE, // PE 4 ** 2 ** PWM2 + PE, // PE 5 ** 3 ** PWM3 + PG, // PG 5 ** 4 ** PWM4 + PE, // PE 3 ** 5 ** PWM5 + PH, // PH 3 ** 6 ** PWM6 + PH, // PH 4 ** 7 ** PWM7 + PH, // PH 5 ** 8 ** PWM8 + PH, // PH 6 ** 9 ** PWM9 + PB, // PB 4 ** 10 ** PWM10 + PB, // PB 5 ** 11 ** PWM11 + PB, // PB 6 ** 12 ** PWM12 + PB, // PB 7 ** 13 ** PWM13 + PJ, // PJ 1 ** 14 ** USART3_TX + PJ, // PJ 0 ** 15 ** USART3_RX + PH, // PH 1 ** 16 ** USART2_TX + PH, // PH 0 ** 17 ** USART2_RX + PD, // PD 3 ** 18 ** USART1_TX + PD, // PD 2 ** 19 ** USART1_RX + PD, // PD 1 ** 20 ** I2C_SDA + PD, // PD 0 ** 21 ** I2C_SCL + PA, // PA 0 ** 22 ** D22 + PA, // PA 1 ** 23 ** D23 + PA, // PA 2 ** 24 ** D24 + PA, // PA 3 ** 25 ** D25 + PA, // PA 4 ** 26 ** D26 + PA, // PA 5 ** 27 ** D27 + PA, // PA 6 ** 28 ** D28 + PA, // PA 7 ** 29 ** D29 + PC, // PC 7 ** 30 ** D30 + PC, // PC 6 ** 31 ** D31 + PC, // PC 5 ** 32 ** D32 + PC, // PC 4 ** 33 ** D33 + PC, // PC 3 ** 34 ** D34 + PC, // PC 2 ** 35 ** D35 + PC, // PC 1 ** 36 ** D36 + PC, // PC 0 ** 37 ** D37 + PD, // PD 7 ** 38 ** D38 + PG, // PG 2 ** 39 ** D39 + PG, // PG 1 ** 40 ** D40 + PG, // PG 0 ** 41 ** D41 + PL, // PL 7 ** 42 ** D42 + PL, // PL 6 ** 43 ** D43 + PL, // PL 5 ** 44 ** D44 + PL, // PL 4 ** 45 ** D45 + PL, // PL 3 ** 46 ** D46 + PL, // PL 2 ** 47 ** D47 + PL, // PL 1 ** 48 ** D48 + PL, // PL 0 ** 49 ** D49 + PB, // PB 3 ** 50 ** SPI_MISO + PB, // PB 2 ** 51 ** SPI_MOSI + PB, // PB 1 ** 52 ** SPI_SCK + PB, // PB 0 ** 53 ** SPI_SS + PF, // PF 0 ** 54 ** A0 + PF, // PF 1 ** 55 ** A1 + PF, // PF 2 ** 56 ** A2 + PF, // PF 3 ** 57 ** A3 + PF, // PF 4 ** 58 ** A4 + PF, // PF 5 ** 59 ** A5 + PF, // PF 6 ** 60 ** A6 + PF, // PF 7 ** 61 ** A7 + PK, // PK 0 ** 62 ** A8 + PK, // PK 1 ** 63 ** A9 + PK, // PK 2 ** 64 ** A10 + PK, // PK 3 ** 65 ** A11 + PK, // PK 4 ** 66 ** A12 + PK, // PK 5 ** 67 ** A13 + PK, // PK 6 ** 68 ** A14 + PK, // PK 7 ** 69 ** A15 + PG, // PG 4 ** 70 ** + PG, // PG 3 ** 71 ** + PJ, // PJ 2 ** 72 ** + PJ, // PJ 3 ** 73 ** + PJ, // PJ 7 ** 74 ** + PJ, // PJ 4 ** 75 ** + PJ, // PJ 5 ** 76 ** + PJ, // PJ 6 ** 77 ** + PE, // PE 2 ** 78 ** + PE, // PE 6 ** 79 ** + PE, // PE 7 ** 80 ** + PD, // PD 4 ** 81 ** + PD, // PD 5 ** 82 ** + PD, // PD 6 ** 83 ** + PH, // PH 2 ** 84 ** + PH, // PH 7 ** 85 ** }; #define digitalPinToPort_plus_70(P) ( pgm_read_byte( digital_pin_to_port_PGM_plus_70 + (P) ) ) @@ -141,180 +141,179 @@ const uint8_t PROGMEM digital_pin_to_port_PGM_plus_70[] = { const uint8_t PROGMEM digital_pin_to_bit_mask_PGM_plus_70[] = { // PIN IN PORT // ------------------------ - _BV( 0 ) , // PE 0 ** 0 ** USART0_RX - _BV( 1 ) , // PE 1 ** 1 ** USART0_TX - _BV( 4 ) , // PE 4 ** 2 ** PWM2 - _BV( 5 ) , // PE 5 ** 3 ** PWM3 - _BV( 5 ) , // PG 5 ** 4 ** PWM4 - _BV( 3 ) , // PE 3 ** 5 ** PWM5 - _BV( 3 ) , // PH 3 ** 6 ** PWM6 - _BV( 4 ) , // PH 4 ** 7 ** PWM7 - _BV( 5 ) , // PH 5 ** 8 ** PWM8 - _BV( 6 ) , // PH 6 ** 9 ** PWM9 - _BV( 4 ) , // PB 4 ** 10 ** PWM10 - _BV( 5 ) , // PB 5 ** 11 ** PWM11 - _BV( 6 ) , // PB 6 ** 12 ** PWM12 - _BV( 7 ) , // PB 7 ** 13 ** PWM13 - _BV( 1 ) , // PJ 1 ** 14 ** USART3_TX - _BV( 0 ) , // PJ 0 ** 15 ** USART3_RX - _BV( 1 ) , // PH 1 ** 16 ** USART2_TX - _BV( 0 ) , // PH 0 ** 17 ** USART2_RX - _BV( 3 ) , // PD 3 ** 18 ** USART1_TX - _BV( 2 ) , // PD 2 ** 19 ** USART1_RX - _BV( 1 ) , // PD 1 ** 20 ** I2C_SDA - _BV( 0 ) , // PD 0 ** 21 ** I2C_SCL - _BV( 0 ) , // PA 0 ** 22 ** D22 - _BV( 1 ) , // PA 1 ** 23 ** D23 - _BV( 2 ) , // PA 2 ** 24 ** D24 - _BV( 3 ) , // PA 3 ** 25 ** D25 - _BV( 4 ) , // PA 4 ** 26 ** D26 - _BV( 5 ) , // PA 5 ** 27 ** D27 - _BV( 6 ) , // PA 6 ** 28 ** D28 - _BV( 7 ) , // PA 7 ** 29 ** D29 - _BV( 7 ) , // PC 7 ** 30 ** D30 - _BV( 6 ) , // PC 6 ** 31 ** D31 - _BV( 5 ) , // PC 5 ** 32 ** D32 - _BV( 4 ) , // PC 4 ** 33 ** D33 - _BV( 3 ) , // PC 3 ** 34 ** D34 - _BV( 2 ) , // PC 2 ** 35 ** D35 - _BV( 1 ) , // PC 1 ** 36 ** D36 - _BV( 0 ) , // PC 0 ** 37 ** D37 - _BV( 7 ) , // PD 7 ** 38 ** D38 - _BV( 2 ) , // PG 2 ** 39 ** D39 - _BV( 1 ) , // PG 1 ** 40 ** D40 - _BV( 0 ) , // PG 0 ** 41 ** D41 - _BV( 7 ) , // PL 7 ** 42 ** D42 - _BV( 6 ) , // PL 6 ** 43 ** D43 - _BV( 5 ) , // PL 5 ** 44 ** D44 - _BV( 4 ) , // PL 4 ** 45 ** D45 - _BV( 3 ) , // PL 3 ** 46 ** D46 - _BV( 2 ) , // PL 2 ** 47 ** D47 - _BV( 1 ) , // PL 1 ** 48 ** D48 - _BV( 0 ) , // PL 0 ** 49 ** D49 - _BV( 3 ) , // PB 3 ** 50 ** SPI_MISO - _BV( 2 ) , // PB 2 ** 51 ** SPI_MOSI - _BV( 1 ) , // PB 1 ** 52 ** SPI_SCK - _BV( 0 ) , // PB 0 ** 53 ** SPI_SS - _BV( 0 ) , // PF 0 ** 54 ** A0 - _BV( 1 ) , // PF 1 ** 55 ** A1 - _BV( 2 ) , // PF 2 ** 56 ** A2 - _BV( 3 ) , // PF 3 ** 57 ** A3 - _BV( 4 ) , // PF 4 ** 58 ** A4 - _BV( 5 ) , // PF 5 ** 59 ** A5 - _BV( 6 ) , // PF 6 ** 60 ** A6 - _BV( 7 ) , // PF 7 ** 61 ** A7 - _BV( 0 ) , // PK 0 ** 62 ** A8 - _BV( 1 ) , // PK 1 ** 63 ** A9 - _BV( 2 ) , // PK 2 ** 64 ** A10 - _BV( 3 ) , // PK 3 ** 65 ** A11 - _BV( 4 ) , // PK 4 ** 66 ** A12 - _BV( 5 ) , // PK 5 ** 67 ** A13 - _BV( 6 ) , // PK 6 ** 68 ** A14 - _BV( 7 ) , // PK 7 ** 69 ** A15 - _BV( 4 ) , // PG 4 ** 70 ** - _BV( 3 ) , // PG 3 ** 71 ** - _BV( 2 ) , // PJ 2 ** 72 ** - _BV( 3 ) , // PJ 3 ** 73 ** - _BV( 7 ) , // PJ 7 ** 74 ** - _BV( 4 ) , // PJ 4 ** 75 ** - _BV( 5 ) , // PJ 5 ** 76 ** - _BV( 6 ) , // PJ 6 ** 77 ** - _BV( 2 ) , // PE 2 ** 78 ** - _BV( 6 ) , // PE 6 ** 79 ** - _BV( 7 ) , // PE 7 ** 80 ** - _BV( 4 ) , // PD 4 ** 81 ** - _BV( 5 ) , // PD 5 ** 82 ** - _BV( 6 ) , // PD 6 ** 83 ** - _BV( 2 ) , // PH 2 ** 84 ** - _BV( 7 ) , // PH 7 ** 85 ** + _BV( 0 ), // PE 0 ** 0 ** USART0_RX + _BV( 1 ), // PE 1 ** 1 ** USART0_TX + _BV( 4 ), // PE 4 ** 2 ** PWM2 + _BV( 5 ), // PE 5 ** 3 ** PWM3 + _BV( 5 ), // PG 5 ** 4 ** PWM4 + _BV( 3 ), // PE 3 ** 5 ** PWM5 + _BV( 3 ), // PH 3 ** 6 ** PWM6 + _BV( 4 ), // PH 4 ** 7 ** PWM7 + _BV( 5 ), // PH 5 ** 8 ** PWM8 + _BV( 6 ), // PH 6 ** 9 ** PWM9 + _BV( 4 ), // PB 4 ** 10 ** PWM10 + _BV( 5 ), // PB 5 ** 11 ** PWM11 + _BV( 6 ), // PB 6 ** 12 ** PWM12 + _BV( 7 ), // PB 7 ** 13 ** PWM13 + _BV( 1 ), // PJ 1 ** 14 ** USART3_TX + _BV( 0 ), // PJ 0 ** 15 ** USART3_RX + _BV( 1 ), // PH 1 ** 16 ** USART2_TX + _BV( 0 ), // PH 0 ** 17 ** USART2_RX + _BV( 3 ), // PD 3 ** 18 ** USART1_TX + _BV( 2 ), // PD 2 ** 19 ** USART1_RX + _BV( 1 ), // PD 1 ** 20 ** I2C_SDA + _BV( 0 ), // PD 0 ** 21 ** I2C_SCL + _BV( 0 ), // PA 0 ** 22 ** D22 + _BV( 1 ), // PA 1 ** 23 ** D23 + _BV( 2 ), // PA 2 ** 24 ** D24 + _BV( 3 ), // PA 3 ** 25 ** D25 + _BV( 4 ), // PA 4 ** 26 ** D26 + _BV( 5 ), // PA 5 ** 27 ** D27 + _BV( 6 ), // PA 6 ** 28 ** D28 + _BV( 7 ), // PA 7 ** 29 ** D29 + _BV( 7 ), // PC 7 ** 30 ** D30 + _BV( 6 ), // PC 6 ** 31 ** D31 + _BV( 5 ), // PC 5 ** 32 ** D32 + _BV( 4 ), // PC 4 ** 33 ** D33 + _BV( 3 ), // PC 3 ** 34 ** D34 + _BV( 2 ), // PC 2 ** 35 ** D35 + _BV( 1 ), // PC 1 ** 36 ** D36 + _BV( 0 ), // PC 0 ** 37 ** D37 + _BV( 7 ), // PD 7 ** 38 ** D38 + _BV( 2 ), // PG 2 ** 39 ** D39 + _BV( 1 ), // PG 1 ** 40 ** D40 + _BV( 0 ), // PG 0 ** 41 ** D41 + _BV( 7 ), // PL 7 ** 42 ** D42 + _BV( 6 ), // PL 6 ** 43 ** D43 + _BV( 5 ), // PL 5 ** 44 ** D44 + _BV( 4 ), // PL 4 ** 45 ** D45 + _BV( 3 ), // PL 3 ** 46 ** D46 + _BV( 2 ), // PL 2 ** 47 ** D47 + _BV( 1 ), // PL 1 ** 48 ** D48 + _BV( 0 ), // PL 0 ** 49 ** D49 + _BV( 3 ), // PB 3 ** 50 ** SPI_MISO + _BV( 2 ), // PB 2 ** 51 ** SPI_MOSI + _BV( 1 ), // PB 1 ** 52 ** SPI_SCK + _BV( 0 ), // PB 0 ** 53 ** SPI_SS + _BV( 0 ), // PF 0 ** 54 ** A0 + _BV( 1 ), // PF 1 ** 55 ** A1 + _BV( 2 ), // PF 2 ** 56 ** A2 + _BV( 3 ), // PF 3 ** 57 ** A3 + _BV( 4 ), // PF 4 ** 58 ** A4 + _BV( 5 ), // PF 5 ** 59 ** A5 + _BV( 6 ), // PF 6 ** 60 ** A6 + _BV( 7 ), // PF 7 ** 61 ** A7 + _BV( 0 ), // PK 0 ** 62 ** A8 + _BV( 1 ), // PK 1 ** 63 ** A9 + _BV( 2 ), // PK 2 ** 64 ** A10 + _BV( 3 ), // PK 3 ** 65 ** A11 + _BV( 4 ), // PK 4 ** 66 ** A12 + _BV( 5 ), // PK 5 ** 67 ** A13 + _BV( 6 ), // PK 6 ** 68 ** A14 + _BV( 7 ), // PK 7 ** 69 ** A15 + _BV( 4 ), // PG 4 ** 70 ** + _BV( 3 ), // PG 3 ** 71 ** + _BV( 2 ), // PJ 2 ** 72 ** + _BV( 3 ), // PJ 3 ** 73 ** + _BV( 7 ), // PJ 7 ** 74 ** + _BV( 4 ), // PJ 4 ** 75 ** + _BV( 5 ), // PJ 5 ** 76 ** + _BV( 6 ), // PJ 6 ** 77 ** + _BV( 2 ), // PE 2 ** 78 ** + _BV( 6 ), // PE 6 ** 79 ** + _BV( 7 ), // PE 7 ** 80 ** + _BV( 4 ), // PD 4 ** 81 ** + _BV( 5 ), // PD 5 ** 82 ** + _BV( 6 ), // PD 6 ** 83 ** + _BV( 2 ), // PH 2 ** 84 ** + _BV( 7 ), // PH 7 ** 85 ** }; #define digitalPinToBitMask_plus_70(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM_plus_70 + (P) ) ) - const uint8_t PROGMEM digital_pin_to_timer_PGM_plus_70[] = { // TIMERS // ------------------------ - NOT_ON_TIMER , // PE 0 ** 0 ** USART0_RX - NOT_ON_TIMER , // PE 1 ** 1 ** USART0_TX - TIMER3B , // PE 4 ** 2 ** PWM2 - TIMER3C , // PE 5 ** 3 ** PWM3 - TIMER0B , // PG 5 ** 4 ** PWM4 - TIMER3A , // PE 3 ** 5 ** PWM5 - TIMER4A , // PH 3 ** 6 ** PWM6 - TIMER4B , // PH 4 ** 7 ** PWM7 - TIMER4C , // PH 5 ** 8 ** PWM8 - TIMER2B , // PH 6 ** 9 ** PWM9 - TIMER2A , // PB 4 ** 10 ** PWM10 - TIMER1A , // PB 5 ** 11 ** PWM11 - TIMER1B , // PB 6 ** 12 ** PWM12 - TIMER0A , // PB 7 ** 13 ** PWM13 - NOT_ON_TIMER , // PJ 1 ** 14 ** USART3_TX - NOT_ON_TIMER , // PJ 0 ** 15 ** USART3_RX - NOT_ON_TIMER , // PH 1 ** 16 ** USART2_TX - NOT_ON_TIMER , // PH 0 ** 17 ** USART2_RX - NOT_ON_TIMER , // PD 3 ** 18 ** USART1_TX - NOT_ON_TIMER , // PD 2 ** 19 ** USART1_RX - NOT_ON_TIMER , // PD 1 ** 20 ** I2C_SDA - NOT_ON_TIMER , // PD 0 ** 21 ** I2C_SCL - NOT_ON_TIMER , // PA 0 ** 22 ** D22 - NOT_ON_TIMER , // PA 1 ** 23 ** D23 - NOT_ON_TIMER , // PA 2 ** 24 ** D24 - NOT_ON_TIMER , // PA 3 ** 25 ** D25 - NOT_ON_TIMER , // PA 4 ** 26 ** D26 - NOT_ON_TIMER , // PA 5 ** 27 ** D27 - NOT_ON_TIMER , // PA 6 ** 28 ** D28 - NOT_ON_TIMER , // PA 7 ** 29 ** D29 - NOT_ON_TIMER , // PC 7 ** 30 ** D30 - NOT_ON_TIMER , // PC 6 ** 31 ** D31 - NOT_ON_TIMER , // PC 5 ** 32 ** D32 - NOT_ON_TIMER , // PC 4 ** 33 ** D33 - NOT_ON_TIMER , // PC 3 ** 34 ** D34 - NOT_ON_TIMER , // PC 2 ** 35 ** D35 - NOT_ON_TIMER , // PC 1 ** 36 ** D36 - NOT_ON_TIMER , // PC 0 ** 37 ** D37 - NOT_ON_TIMER , // PD 7 ** 38 ** D38 - NOT_ON_TIMER , // PG 2 ** 39 ** D39 - NOT_ON_TIMER , // PG 1 ** 40 ** D40 - NOT_ON_TIMER , // PG 0 ** 41 ** D41 - NOT_ON_TIMER , // PL 7 ** 42 ** D42 - NOT_ON_TIMER , // PL 6 ** 43 ** D43 - TIMER5C , // PL 5 ** 44 ** D44 - TIMER5B , // PL 4 ** 45 ** D45 - TIMER5A , // PL 3 ** 46 ** D46 - NOT_ON_TIMER , // PL 2 ** 47 ** D47 - NOT_ON_TIMER , // PL 1 ** 48 ** D48 - NOT_ON_TIMER , // PL 0 ** 49 ** D49 - NOT_ON_TIMER , // PB 3 ** 50 ** SPI_MISO - NOT_ON_TIMER , // PB 2 ** 51 ** SPI_MOSI - NOT_ON_TIMER , // PB 1 ** 52 ** SPI_SCK - NOT_ON_TIMER , // PB 0 ** 53 ** SPI_SS - NOT_ON_TIMER , // PF 0 ** 54 ** A0 - NOT_ON_TIMER , // PF 1 ** 55 ** A1 - NOT_ON_TIMER , // PF 2 ** 56 ** A2 - NOT_ON_TIMER , // PF 3 ** 57 ** A3 - NOT_ON_TIMER , // PF 4 ** 58 ** A4 - NOT_ON_TIMER , // PF 5 ** 59 ** A5 - NOT_ON_TIMER , // PF 6 ** 60 ** A6 - NOT_ON_TIMER , // PF 7 ** 61 ** A7 - NOT_ON_TIMER , // PK 0 ** 62 ** A8 - NOT_ON_TIMER , // PK 1 ** 63 ** A9 - NOT_ON_TIMER , // PK 2 ** 64 ** A10 - NOT_ON_TIMER , // PK 3 ** 65 ** A11 - NOT_ON_TIMER , // PK 4 ** 66 ** A12 - NOT_ON_TIMER , // PK 5 ** 67 ** A13 - NOT_ON_TIMER , // PK 6 ** 68 ** A14 - NOT_ON_TIMER , // PK 7 ** 69 ** A15 - NOT_ON_TIMER , // PG 4 ** 70 ** - NOT_ON_TIMER , // PG 3 ** 71 ** - NOT_ON_TIMER , // PJ 2 ** 72 ** - NOT_ON_TIMER , // PJ 3 ** 73 ** - NOT_ON_TIMER , // PJ 7 ** 74 ** - NOT_ON_TIMER , // PJ 4 ** 75 ** - NOT_ON_TIMER , // PJ 5 ** 76 ** - NOT_ON_TIMER , // PJ 6 ** 77 ** - NOT_ON_TIMER , // PE 2 ** 78 ** - NOT_ON_TIMER , // PE 6 ** 79 ** + NOT_ON_TIMER, // PE 0 ** 0 ** USART0_RX + NOT_ON_TIMER, // PE 1 ** 1 ** USART0_TX + TIMER3B, // PE 4 ** 2 ** PWM2 + TIMER3C, // PE 5 ** 3 ** PWM3 + TIMER0B, // PG 5 ** 4 ** PWM4 + TIMER3A, // PE 3 ** 5 ** PWM5 + TIMER4A, // PH 3 ** 6 ** PWM6 + TIMER4B, // PH 4 ** 7 ** PWM7 + TIMER4C, // PH 5 ** 8 ** PWM8 + TIMER2B, // PH 6 ** 9 ** PWM9 + TIMER2A, // PB 4 ** 10 ** PWM10 + TIMER1A, // PB 5 ** 11 ** PWM11 + TIMER1B, // PB 6 ** 12 ** PWM12 + TIMER0A, // PB 7 ** 13 ** PWM13 + NOT_ON_TIMER, // PJ 1 ** 14 ** USART3_TX + NOT_ON_TIMER, // PJ 0 ** 15 ** USART3_RX + NOT_ON_TIMER, // PH 1 ** 16 ** USART2_TX + NOT_ON_TIMER, // PH 0 ** 17 ** USART2_RX + NOT_ON_TIMER, // PD 3 ** 18 ** USART1_TX + NOT_ON_TIMER, // PD 2 ** 19 ** USART1_RX + NOT_ON_TIMER, // PD 1 ** 20 ** I2C_SDA + NOT_ON_TIMER, // PD 0 ** 21 ** I2C_SCL + NOT_ON_TIMER, // PA 0 ** 22 ** D22 + NOT_ON_TIMER, // PA 1 ** 23 ** D23 + NOT_ON_TIMER, // PA 2 ** 24 ** D24 + NOT_ON_TIMER, // PA 3 ** 25 ** D25 + NOT_ON_TIMER, // PA 4 ** 26 ** D26 + NOT_ON_TIMER, // PA 5 ** 27 ** D27 + NOT_ON_TIMER, // PA 6 ** 28 ** D28 + NOT_ON_TIMER, // PA 7 ** 29 ** D29 + NOT_ON_TIMER, // PC 7 ** 30 ** D30 + NOT_ON_TIMER, // PC 6 ** 31 ** D31 + NOT_ON_TIMER, // PC 5 ** 32 ** D32 + NOT_ON_TIMER, // PC 4 ** 33 ** D33 + NOT_ON_TIMER, // PC 3 ** 34 ** D34 + NOT_ON_TIMER, // PC 2 ** 35 ** D35 + NOT_ON_TIMER, // PC 1 ** 36 ** D36 + NOT_ON_TIMER, // PC 0 ** 37 ** D37 + NOT_ON_TIMER, // PD 7 ** 38 ** D38 + NOT_ON_TIMER, // PG 2 ** 39 ** D39 + NOT_ON_TIMER, // PG 1 ** 40 ** D40 + NOT_ON_TIMER, // PG 0 ** 41 ** D41 + NOT_ON_TIMER, // PL 7 ** 42 ** D42 + NOT_ON_TIMER, // PL 6 ** 43 ** D43 + TIMER5C, // PL 5 ** 44 ** D44 + TIMER5B, // PL 4 ** 45 ** D45 + TIMER5A, // PL 3 ** 46 ** D46 + NOT_ON_TIMER, // PL 2 ** 47 ** D47 + NOT_ON_TIMER, // PL 1 ** 48 ** D48 + NOT_ON_TIMER, // PL 0 ** 49 ** D49 + NOT_ON_TIMER, // PB 3 ** 50 ** SPI_MISO + NOT_ON_TIMER, // PB 2 ** 51 ** SPI_MOSI + NOT_ON_TIMER, // PB 1 ** 52 ** SPI_SCK + NOT_ON_TIMER, // PB 0 ** 53 ** SPI_SS + NOT_ON_TIMER, // PF 0 ** 54 ** A0 + NOT_ON_TIMER, // PF 1 ** 55 ** A1 + NOT_ON_TIMER, // PF 2 ** 56 ** A2 + NOT_ON_TIMER, // PF 3 ** 57 ** A3 + NOT_ON_TIMER, // PF 4 ** 58 ** A4 + NOT_ON_TIMER, // PF 5 ** 59 ** A5 + NOT_ON_TIMER, // PF 6 ** 60 ** A6 + NOT_ON_TIMER, // PF 7 ** 61 ** A7 + NOT_ON_TIMER, // PK 0 ** 62 ** A8 + NOT_ON_TIMER, // PK 1 ** 63 ** A9 + NOT_ON_TIMER, // PK 2 ** 64 ** A10 + NOT_ON_TIMER, // PK 3 ** 65 ** A11 + NOT_ON_TIMER, // PK 4 ** 66 ** A12 + NOT_ON_TIMER, // PK 5 ** 67 ** A13 + NOT_ON_TIMER, // PK 6 ** 68 ** A14 + NOT_ON_TIMER, // PK 7 ** 69 ** A15 + NOT_ON_TIMER, // PG 4 ** 70 ** + NOT_ON_TIMER, // PG 3 ** 71 ** + NOT_ON_TIMER, // PJ 2 ** 72 ** + NOT_ON_TIMER, // PJ 3 ** 73 ** + NOT_ON_TIMER, // PJ 7 ** 74 ** + NOT_ON_TIMER, // PJ 4 ** 75 ** + NOT_ON_TIMER, // PJ 5 ** 76 ** + NOT_ON_TIMER, // PJ 6 ** 77 ** + NOT_ON_TIMER, // PE 2 ** 78 ** + NOT_ON_TIMER, // PE 6 ** 79 ** }; #define digitalPinToTimer_plus_70(P) ( pgm_read_byte( digital_pin_to_timer_PGM_plus_70 + (P) ) ) diff --git a/Marlin/src/HAL/AVR/registers.cpp b/Marlin/src/HAL/AVR/registers.cpp new file mode 100644 index 0000000000..08a74c952a --- /dev/null +++ b/Marlin/src/HAL/AVR/registers.cpp @@ -0,0 +1,979 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef __AVR__ + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(HAL_AVR_DIRTY_INIT) + +#include "registers.h" + +// Since the compiler could be creating multiple copies of function code-graphs for each header inline-inclusion, +// we want to off-load the function definitions that define static memory into this solitary compilation unit. +// This way the ROM is NOT bloated (who knows if the compiler is optimizing same-content constant objects into one?) + +ATmegaPinFunctions _ATmega_getPinFunctions(int pin) { + if (pin < 0) return {}; + + ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); + + #ifdef __AVR_TRM01__ + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0A, eATmegaPinFunc::TOC1C, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART1_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT3, eATmegaPinFunc::USART1_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT2, eATmegaPinFunc::USART1_RXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT7, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::CLKO }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT6, eATmegaPinFunc::TIMER3_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::TOC3C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::TOC3B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC3A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::USART0_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDO, eATmegaPinFunc::USART0_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDI, eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_F) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_G) { + if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3 ) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_ALE }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_RD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_WR }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_H) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER4_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_RXD }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_J) { + if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_CLK, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_RXD, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_K) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC15, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC14, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC13, eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC12, eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC11, eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC10, eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC9, eATmegaPinFunc::PCI17 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC8, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_L) { + if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER5_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER5_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER4_ICP }; + return { funcs, countof(funcs) }; + } + } + #elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI7, eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI6, eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI5, eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI4, eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI3, eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI2, eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI1, eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI0, eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::TOC3B, eATmegaPinFunc::PCI15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::TOC3A, eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::EINT2, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::CLKO, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI17, eATmegaPinFunc::TWI_SDA }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI31 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI30 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI29 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::PCI28 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::PCI27 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::PCI26 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI25 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI24, eATmegaPinFunc::TIMER3_ECI }; + return { funcs, countof(funcs) }; + } + } + #elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::XTAL2, eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::XTAL1, eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::CLKO, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_CLK, eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_TXD, eATmegaPinFunc::PCI17 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_RXD, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + #elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0A, eATmegaPinFunc::TOC1C, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDO, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDI, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::CLKO }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::TOC3A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::TOC3B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::TOC3C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::TIMER3_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART1_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT3, eATmegaPinFunc::USART1_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT2, eATmegaPinFunc::USART1_RXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TOC2B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TOC0B }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT7, eATmegaPinFunc::AIN1, eATmegaPinFunc::UVCON }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT6, eATmegaPinFunc::AIN0 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::UID }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_ALE }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_RD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_WR }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_F) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } + #elif defined(__AVR_TRM05__) + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::EINT2, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::CLKO, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::PCI17 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI31 }; + return { funcs, countof(funcs) }; + } + if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI30 }; + return { funcs, countof(funcs) }; + } + if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI29 }; + return { funcs, countof(funcs) }; + } + if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::PCI28 }; + return { funcs, countof(funcs) }; + } + if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::PCI27 }; + return { funcs, countof(funcs) }; + } + if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::PCI26 }; + return { funcs, countof(funcs) }; + } + if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI25 }; + return { funcs, countof(funcs) }; + } + if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::PCI24 }; + return { funcs, countof(funcs) }; + } + } + #endif + + return ATmegaPinFunctions(); // default and empty. +} + +#endif // HAL_AVR_DIRTY_INIT +#endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h new file mode 100644 index 0000000000..0eac4888cd --- /dev/null +++ b/Marlin/src/HAL/AVR/registers.h @@ -0,0 +1,5080 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include + +// This volatile-nonsense has to be done due to the C++ platform language specialization that specifies, for it's own compiler ideology, +// that memory writes and reads can be optimized across easily-reachable code spaces. This is in contrast to MSVC which specifies that +// memory writes and reads are holy. + +// OVERVIEW OF PREPROCESSOR DEFINITIONS: +// __AVR_ATmega2560__ +// __AVR_ATmega1284P__ +// __AVR_ATmega1280__ +// __AVR_ATmega644__ +// __AVR_ATmega644P__ +// __AVR_ATmega2561__ + +// Contributed by Martin Turski, company owner of EirDev, on the 29th of November, 2022 +// Contact E-Mail: turningtides@outlook.de +// Created specifically for the Marlin FW for AVR backwards-compatibility. +// Please expand this file with details of every supported AVR implementation. +// 1) download the latest technical reference manual +// 2) add the new technical reference manual below using a set of __AVR_*__ preprocessor definitions and a new __AVR_TRM*__ incrementing define +// 3) check which of the existing AVR registers exist on the new implementation and enable them +// 4) add any new register definitions +// 5) add the register memory layout below the definitions +// 6) extend the _ATmega_resetperipherals functions +// 7) extend the _ATmega_savePinAlternate function +// 8) copy the extension idea to _ATmega_restorePinAlternate and finish implementing it +// You need to adjust the eATmegaPort enumeration aswell. + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + #error "Fatal error: __AVR_TRMn__ already defined! (n: 01|02|03|04|05)" +#endif + +#if defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega640__) + // ATmega2560 technical reference manual date: 28th of November, 2022 + // ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf + #define __AVR_TRM01__ +#elif defined(__AVR_ATmega164A__) || defined(__AVR_ATmega164PA__) || defined(__AVR_ATmega324A__) || defined(__AVR_ATmega324PA__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) + // ATmega1284 technical reference manual date: 29th of November, 2022 + // ATmega164A_PA-324A_PA-644A_PA-1284_P_Data-Sheet-40002070B.pdf + #define __AVR_TRM02__ +#elif defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) || defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) + // ATmega328 technical reference manual date: 29th of November, 2022 + // ATmega48A-PA-88A-PA-168A-PA-328-P-DS-DS40002061B.pdf + #define __AVR_TRM03__ +#elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__) + // AT90USB1287 technical reference manual ID: 7593D–AVR–07/06 + // Preliminary. + #define __AVR_TRM04__ +#elif defined(__AVR_ATmega164P__) || defined(__AVR_ATmega164V__) || defined(__AVR_ATmega324P__) || defined(__AVR_ATmega324V__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644V__) + // ATmega644P technical reference manual date: 14th of February, 2023 + // ATmega164P-324P-644P-Data-Sheet-40002071A.pdf + #define __AVR_TRM05__ +#endif + +/** + * HELPER FUNCTIONS + */ +namespace AVRHelpers { + + template + struct no_volatile { + typedef T type; + }; + + template + struct no_volatile : public no_volatile {}; + + template + struct voltype { + typedef T type; + }; + template + struct voltype { + typedef uint8_t type; + }; + template + struct voltype { + typedef uint16_t type; + }; + template + struct voltype { + typedef uint32_t type; + }; + + template + inline void dwrite(volatile T& v, const T& V) noexcept { + (volatile typename voltype ::type&)v = (const typename voltype ::type&)V; + } + +} // namespace AVRHelpers + +// As old as the ATmega series of CPU is, the worse the actual libraries making +// use of the MCU likely are. + +// These registers as references do not take program space since they are purely references. + +// It would be great if the old AVR definitions could be wasted in favor of these +// and code be rewritten to use the following more robust definitions. + +struct _bit_reg_t { + uint8_t val; + + bool getValue(uint8_t idx) const volatile { + return ( val & (1 << idx) ); + } + void setValue(uint8_t idx, bool value) volatile { + if (value) + val |= (1 << idx); + else + val &= ~(1 << idx); + } +}; + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + typedef _bit_reg_t PIN_reg_t; + typedef _bit_reg_t DDR_reg_t; + typedef _bit_reg_t PORT_reg_t; + + struct PORT_dev_t { + PIN_reg_t _PIN; + DDR_reg_t _DDR; + PORT_reg_t _PORT; + + inline void operator = ( const PORT_dev_t& r ) volatile { + using namespace AVRHelpers; + dwrite(this->_PIN, r._PIN); + dwrite(this->_DDR, r._DDR); + dwrite(this->_PORT, r._PORT); + } + }; + static_assert(sizeof(PORT_dev_t) == 3, "invalid size of ATmega2560 GPIO_dev_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM03__ || __AVR_TRM04__ || __AVR_TRM05__ + +#ifdef __AVR_TRM01__ + + struct _bitG_reg_t { + uint8_t val : 6; + uint8_t reserved1 : 2; + + bool getValue(uint8_t idx) const volatile { + return val & (1 << idx); + } + void setValue(uint8_t idx, bool value) volatile { + if (value) + val |= (1 << idx); + else + val &= ~(1 << idx); + } + }; + typedef _bitG_reg_t PING_reg_t; + typedef _bitG_reg_t DDRG_reg_t; + typedef _bitG_reg_t PORTG_reg_t; + + struct PORTG_dev_t { + PING_reg_t _PIN; + DDRG_reg_t _DDR; + PORTG_reg_t _PORT; + + inline void operator = ( const PORTG_dev_t& r ) volatile { + using namespace AVRHelpers; + dwrite(this->_PIN, r._PIN); + dwrite(this->_DDR, r._DDR); + dwrite(this->_PORT, r._PORT); + } + }; + +#endif + +#ifdef __AVR_TRM03__ + + struct _bitC_reg_t { + uint8_t val : 7; + uint8_t reserved1 : 1; + + bool getValue(uint8_t idx) const volatile { + return ( val & (1 << idx) ); + } + void setValue(uint8_t idx, bool value) volatile { + if (value) + val |= (1 << idx); + else + val &= ~(1 << idx); + } + }; + typedef _bitC_reg_t PINC_reg_t; + typedef _bitC_reg_t DDRC_reg_t; + typedef _bitC_reg_t PORTC_reg_t; + + struct PORTC_dev_t { + PINC_reg_t _PIN; + DDRC_reg_t _DDR; + PORTC_reg_t _PORT; + + inline void operator = ( const PORTC_dev_t& r ) volatile { + this->_PIN = r._PIN; + this->_DDR = r._DDR; + this->_PORT = r._PORT; + } + }; + +#endif + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + struct TIFR0_reg_t { + uint8_t _TOV0 : 1; + uint8_t _OCF0A : 1; + uint8_t _OCF0B : 1; + uint8_t reserved1 : 5; + }; + static_assert(sizeof(TIFR0_reg_t) == 1, "invalid size of ATmega2560 TIFR0_reg_t"); + + struct TIFR1_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _TOV1 : 1; + uint8_t _OCF1A : 1; + uint8_t _OCF1B : 1; + uint8_t _OCF1C : 1; + uint8_t reserved1 : 1; + uint8_t _ICF1 : 1; + uint8_t reserved2 : 2; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + uint8_t _TOV1 : 1; + uint8_t _OCF1A : 1; + uint8_t _OCF1B : 1; + uint8_t reserved1 : 2; + uint8_t _ICF1 : 1; + uint8_t reserved2 : 2; + #endif + }; + static_assert(sizeof(TIFR1_reg_t) == 1, "invalid size of ATmega2560 TIFR1_reg_t"); + + struct TIFR2_reg_t { + uint8_t _TOV2 : 1; + uint8_t _OCF2A : 1; + uint8_t _OCF2B : 1; + uint8_t reserved1 : 5; + }; + static_assert(sizeof(TIFR2_reg_t) == 1, "invalid size of ATmega2560 TIFR2_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM03__ || __AVR_TRM04__ || __AVR_TRM05__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + + struct TIFR3_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _TOV3 : 1; + uint8_t _OCF3A : 1; + uint8_t _OCF3B : 1; + uint8_t _OCF3C : 1; + uint8_t reserved1 : 1; + uint8_t _ICF3 : 1; + uint8_t reserved2 : 2; + #elif defined(__AVR_TRM02__) + uint8_t _TOV3 : 1; + uint8_t _OCF3A : 1; + uint8_t _OCF3B : 1; + uint8_t reserved1 : 2; + uint8_t _ICF3 : 1; + uint8_t reserved2 : 2; + #endif + }; + static_assert(sizeof(TIFR3_reg_t) == 1, "invalid size of ATmega2560 TIFR3_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM04__ + +#ifdef __AVR_TRM01__ + + struct TIFR4_reg_t { + uint8_t _TOV4 : 1; + uint8_t _OCF4A : 1; + uint8_t _OCF4B : 1; + uint8_t _OCF4C : 1; + uint8_t reserved1 : 1; + uint8_t _ICF4 : 1; + uint8_t reserved2 : 2; + }; + static_assert(sizeof(TIFR4_reg_t) == 1, "invalid size of ATmega2560 TIFR4_reg_t"); + + struct TIFR5_reg_t { + uint8_t _TOV5 : 1; + uint8_t _OCF5A : 1; + uint8_t _OCF5B : 1; + uint8_t _OCF5C : 1; + uint8_t reserved1 : 1; + uint8_t _ICF5 : 1; + uint8_t reserved2 : 2; + }; + static_assert(sizeof(TIFR5_reg_t) == 1, "invalid size of ATmega2560 TIFR5_reg_t"); + +#endif // __AVR_TRM01__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + struct PCIFR_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) + uint8_t _PCIF0 : 1; + uint8_t _PCIF1 : 1; + uint8_t _PCIF2 : 1; + uint8_t reserved1 : 5; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + uint8_t _PCIF0 : 1; + uint8_t _PCIF1 : 1; + uint8_t _PCIF2 : 1; + uint8_t _PCIF3 : 1; + uint8_t reserved1 : 4; + #elif defined(__AVR_TRM04__) + uint8_t _PCIF0 : 1; + uint8_t reserved1 : 7; + #endif + }; + static_assert(sizeof(PCIFR_reg_t) == 1, "invalid size of ATmega2560 PCIFR_reg_t"); + + struct EIFR_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _INTF0 : 1; + uint8_t _INTF1 : 1; + uint8_t _INTF2 : 1; + uint8_t _INTF3 : 1; + uint8_t _INTF4 : 1; + uint8_t _INTF5 : 1; + uint8_t _INTF6 : 1; + uint8_t _INTF7 : 1; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + uint8_t _INTF0 : 1; + uint8_t _INTF1 : 1; + uint8_t _INTF2 : 1; + uint8_t reserved1 : 5; + #elif defined(__AVR_TRM03__) + uint8_t _INTF0 : 1; + uint8_t _INTF1 : 1; + uint8_t reserved1 : 6; + #endif + }; + static_assert(sizeof(EIFR_reg_t) == 1, "invalid size of ATmega2560 EIFR_reg_t"); + + struct EIMSK_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _INT0 : 1; + uint8_t _INT1 : 1; + uint8_t _INT2 : 1; + uint8_t _INT3 : 1; + uint8_t _INT4 : 1; + uint8_t _INT5 : 1; + uint8_t _INT6 : 1; + uint8_t _INT7 : 1; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + uint8_t _INT0 : 1; + uint8_t _INT1 : 1; + uint8_t _INT2 : 1; + uint8_t reserved1 : 5; + #elif defined(__AVR_TRM03__) + uint8_t _INT0 : 1; + uint8_t _INT1 : 1; + uint8_t reserved1 : 6; + #endif + }; + static_assert(sizeof(EIMSK_reg_t) == 1, "invalid size of ATmega2560 EIMSK_reg_t"); + + struct EECR_reg_t { + uint8_t _EERE : 1; + uint8_t _EEPE : 1; + uint8_t _EEMPE : 1; + uint8_t _EERIE : 1; + uint8_t _EEPM0 : 1; + uint8_t _EEPM1 : 1; + uint8_t reserved1 : 2; + }; + static_assert(sizeof(EECR_reg_t) == 1, "invalid size of ATmega2560 EECR_reg_t"); + + struct EEAR_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + uint16_t _EEAR : 12; + uint16_t reserved1 : 4; + #elif defined(__AVR_TRM03__) + #if defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328P__) + uint16_t _EEAR : 16; + #else + uint8_t _EEAR : 8; + uint8_t reserved1 : 8; + #endif + #endif + }; + static_assert(sizeof(EEAR_reg_t) == 2, "invalid size of ATmega2560 EEAR_reg_t"); + + struct GTCCR_reg_t { + uint8_t _PSRSYNC : 1; + uint8_t _PSRASY : 1; + uint8_t reserved1 : 5; + uint8_t _TSM : 1; + }; + static_assert(sizeof(GTCCR_reg_t) == 1, "invalid size of ATmega2560 GTCCR_reg_t"); + + struct SPCR_reg_t { + uint8_t _SPR : 2; + uint8_t _CPHA : 1; + uint8_t _CPOL : 1; + uint8_t _MSTR : 1; + uint8_t _DORD : 1; + uint8_t _SPE : 1; + uint8_t _SPIE : 1; + }; + static_assert(sizeof(SPCR_reg_t) == 1, "invalid size of ATmega2560 SPCR_reg_t"); + + struct SPSR_reg_t { + uint8_t _SPI2X : 1; + uint8_t reserved1 : 5; + uint8_t _WCOL : 1; + uint8_t _SPIF : 1; + }; + static_assert(sizeof(SPSR_reg_t) == 1, "invalid size of ATmega2560 SPSR_reg_t"); + + struct ACSR_reg_t { + uint8_t _ACIS : 2; + uint8_t _ACIC : 1; + uint8_t _ACIE : 1; + uint8_t _ACI : 1; + uint8_t _ACO : 1; + uint8_t _ACBG : 1; + uint8_t _ACD : 1; + }; + static_assert(sizeof(ACSR_reg_t) == 1, "invalid size of ATmega2560 ACSR_reg_t"); + + struct SMCR_reg_t { + uint8_t _SE : 1; + uint8_t _SM : 3; + uint8_t reserved1 : 4; + }; + static_assert(sizeof(SMCR_reg_t) == 1, "invalid size of ATmega2560 SMCR_reg_t"); + + struct MCUSR_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + uint8_t _PORF : 1; + uint8_t _EXTRF : 1; + uint8_t _BORF : 1; + uint8_t _WDRF : 1; + uint8_t _JTRF : 1; + uint8_t reserved1 : 3; + #elif defined(__AVR_TRM03__) + uint8_t _PORF : 1; + uint8_t _EXTRF : 1; + uint8_t _BORF : 1; + uint8_t _WDRF : 1; + uint8_t reserved1 : 4; + #endif + }; + static_assert(sizeof(MCUSR_reg_t) == 1, "invalid size of ATmega2560 MCUSR_reg_t"); + + struct MCUCR_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _IVCE : 1; + uint8_t _IVSEL : 1; + uint8_t reserved1 : 2; + uint8_t _PUD : 1; + uint8_t reserved2 : 2; + uint8_t _JTD : 1; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + uint8_t _IVCE : 1; + uint8_t _IVSEL : 1; + uint8_t reserved1 : 2; + uint8_t _PUD : 1; + uint8_t _BODSE : 1; + uint8_t _BODS : 1; + uint8_t _JTD : 1; + #elif defined(__AVR_TRM03__) + uint8_t _IVCE : 1; + uint8_t _IVSEL : 1; + uint8_t reserved1 : 2; + uint8_t _PUD : 1; + uint8_t _BODSE : 1; + uint8_t _BODS : 1; + uint8_t reserved2 : 1; + #endif + }; + static_assert(sizeof(MCUCR_reg_t) == 1, "invalid size of ATmega2560 MCUCR_reg_t"); + + struct SPMCSR_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + uint8_t _SPMEN : 1; + uint8_t _PGERS : 1; + uint8_t _PGWRT : 1; + uint8_t _BLBSET : 1; + uint8_t _RWWSRE : 1; + uint8_t _SIGRD : 1; + uint8_t _RWWSB : 1; + uint8_t _SPMIE : 1; + #elif defined(__AVR_TRM03__) + #if defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328P__) + uint8_t _SPMEN : 1; + uint8_t _PGERS : 1; + uint8_t _PGWRT : 1; + uint8_t _BLBSET : 1; + uint8_t _RWWSRE : 1; + uint8_t _SIGRD : 1; + uint8_t _RWWSB : 1; + uint8_t _SPMIE : 1; + #else + uint8_t _SPMEN : 1; + uint8_t _PGERS : 1; + uint8_t _PGWRT : 1; + uint8_t _BLBSET : 1; + uint8_t reserved1 : 1; + uint8_t _SIGRD : 1; + uint8_t reserved2 : 1; + uint8_t _SPMIE : 1; + #endif + #endif + }; + static_assert(sizeof(SPMCSR_reg_t) == 1, "invalid size of ATmega2560 SPMCSR_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM03__ || __AVR_TRM04__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + struct RAMPZ_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + uint8_t _RAMPZ : 2; + uint8_t reserved1 : 6; + #elif defined(__AVR_TRM05__) + uint8_t _RAMPZ : 1; + uint8_t reserved1 : 7; + #endif + }; + static_assert(sizeof(RAMPZ_reg_t) == 1, "invalid size of ATmega2560 RAMPZ_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM04__ || __AVR_TRM05__ + +#ifdef __AVR_TRM01__ + + struct EIND_reg_t { + uint8_t _EIND0 : 1; + uint8_t reserved1 : 7; + }; + static_assert(sizeof(EIND_reg_t) == 1, "invalid size of ATmega2560 EIND_reg_t"); + +#endif // __AVR_TRM01__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + struct SP_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + uint16_t _SP; + #elif defined(__AVR_TRM03__) + #if defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328P__) + uint16_t _SP : 11; + uint16_t reserved1 : 5; + #else + uint16_t _SP : 10; + uint16_t reserved1 : 6; + #endif + #endif + }; + static_assert(sizeof(SP_reg_t) == 2, "invalid size of ATmega2560 SP_reg_t"); + + struct SREG_reg_t { + uint8_t _C : 1; + uint8_t _Z : 1; + uint8_t _N : 1; + uint8_t _V : 1; + uint8_t _S : 1; + uint8_t _H : 1; + uint8_t _T : 1; + uint8_t _I : 1; + }; + static_assert(sizeof(SREG_reg_t) == 1, "invalid size of ATmega2560 SREG_reg_t"); + + struct WDTCSR_reg_t { + uint8_t _WDP0 : 1; + uint8_t _WDP1 : 1; + uint8_t _WDP2 : 1; + uint8_t _WDE : 1; + uint8_t _WDCE : 1; + uint8_t _WDP3 : 1; + uint8_t _WDIE : 1; + uint8_t _WDIF : 1; + }; + static_assert(sizeof(WDTCSR_reg_t) == 1, "invalid size of ATmega2560 WDTCSR_reg_t"); + + struct CLKPR_reg_t { + uint8_t _CLKPS : 4; + uint8_t reserved1 : 3; + uint8_t _CLKPCE : 1; + }; + static_assert(sizeof(CLKPR_reg_t) == 1, "invalid size of ATmega2560 CLKPR_reg_t"); + + struct PRR0_reg_t { + #ifdef __AVR_TRM01__ + uint8_t _PRADC : 1; + uint8_t _PRUSART0 : 1; + uint8_t _PRSPI : 1; + uint8_t _PRTIM1 : 1; + uint8_t reserved1 : 1; + uint8_t _PRTIM0 : 1; + uint8_t _PRTIM2 : 1; + uint8_t _PRTWI : 1; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + uint8_t _PRADC : 1; + uint8_t _PRUSART0 : 1; + uint8_t _PRSPI : 1; + uint8_t _PRTIM1 : 1; + uint8_t _PRUSART1 : 1; + uint8_t _PRTIM0 : 1; + uint8_t _PRTIM2 : 1; + uint8_t _PRTWI : 1; + #elif defined(__AVR_TRM03__) + uint8_t _PRADC : 1; + uint8_t _PRUSART0 : 1; + uint8_t _PRSPI : 1; + uint8_t _PRTIM1 : 1; + uint8_t reserved1 : 1; + uint8_t _PRTIM0 : 1; + uint8_t _PRTIM2 : 1; + uint8_t _PRTWI : 1; + #elif defined(__AVR_TRM04__) + uint8_t _PRADC : 1; + uint8_t reserved1 : 1; + uint8_t _PRSPI : 1; + uint8_t _PRTIM1 : 1; + uint8_t reserved2 : 1; + uint8_t _PRTIM0 : 1; + uint8_t _PRTIM2 : 1; + uint8_t _PRTWI : 1; + #endif + }; + static_assert(sizeof(PRR0_reg_t) == 1, "invalid size of ATmega2560 PRR0_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM03__ || __AVR_TRM04__ || __AVR_TRM05__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + + struct PRR1_reg_t { + #ifdef __AVR_TRM01__ + uint8_t _PRUSART1 : 1; + uint8_t _PRUSART2 : 1; + uint8_t _PRUSART3 : 1; + uint8_t _PRTIM3 : 1; + uint8_t _PRTIM4 : 1; + uint8_t _PRTIM5 : 1; + uint8_t reserved1 : 2; + #elif defined(__AVR_TRM02__) + uint8_t _PRTIM3 : 1; + uint8_t reserved1 : 7; + #elif defined(__AVR_TRM04__) + uint8_t _PRUSART1 : 1; + uint8_t reserved1 : 2; + uint8_t _PRTIM3 : 1; + uint8_t reserved2 : 3; + uint8_t _PRUSB : 1; + #endif + }; + static_assert(sizeof(PRR1_reg_t) == 1, "invalid size of ATmega2560 PRR1_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM04__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + struct PCICR_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; + uint8_t _PCIE2 : 1; + uint8_t reserved1 : 5; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; + uint8_t _PCIE2 : 1; + uint8_t _PCIE3 : 1; + uint8_t reserved1 : 4; + #elif defined(__AVR_TRM04__) + uint8_t _PCIE0 : 1; + uint8_t reserved1 : 7; + #endif + }; + static_assert(sizeof(PCICR_reg_t) == 1, "invalid size of ATmega2560 PCICR_reg_t"); + + struct EICRA_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _ISC0 : 2; + uint8_t _ISC1 : 2; + uint8_t _ISC2 : 2; + uint8_t _ISC3 : 2; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + uint8_t _ISC0 : 2; + uint8_t _ISC1 : 2; + uint8_t _ISC2 : 2; + uint8_t reserved1 : 2; + #elif defined(__AVR_TRM03__) + uint8_t _ISC0 : 2; + uint8_t _ISC1 : 2; + uint8_t reserved1 : 4; + #endif + }; + static_assert(sizeof(EICRA_reg_t) == 1, "invalid size of ATmega2560 EICRA_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM03__ || __AVR_TRM04__ || __AVR_TRM05__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + + struct EICRB_reg_t { + uint8_t _ISC4 : 2; + uint8_t _ISC5 : 2; + uint8_t _ISC6 : 2; + uint8_t _ISC7 : 2; + }; + static_assert(sizeof(EICRB_reg_t) == 1, "invalid size of ATmega2560 EICRB_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM04__ + +#if defined(__AVR_TRM03__) + + struct _bitPCMSK1_reg_t { + uint8_t val : 7; + uint8_t reserved1 : 1; + + bool getValue(uint8_t idx) { return val & (1 << idx); } + void setValue(uint8_t idx, bool value) { + if (value) + val |= (1 << idx); + else + val &= ~(1 << idx); + } + }; + +#endif // __AVR_TRM03__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + struct TIMSK0_reg_t { + #ifdef __AVR_TRM01__ + uint8_t _TOIE0 : 1; + uint8_t _OCIE0A : 1; + uint8_t _OCIE0B : 1; + uint8_t _OCIE0C : 1; + uint8_t reserved1 : 1; + uint8_t _ICIE0 : 1; + uint8_t reserved2 : 2; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + uint8_t _TOIE0 : 1; + uint8_t _OCIE0A : 1; + uint8_t _OCIE0B : 1; + uint8_t reserved1 : 5; + #endif + }; + static_assert(sizeof(TIMSK0_reg_t) == 1, "invalid size of ATmega2560 TIMSK0_reg_t"); + + struct TIMSK1_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _TOIE1 : 1; + uint8_t _OCIE1A : 1; + uint8_t _OCIE1B : 1; + uint8_t _OCIE1C : 1; + uint8_t reserved1 : 1; + uint8_t _ICIE1: 1; + uint8_t reserved2 : 2; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + uint8_t _TOIE1 : 1; + uint8_t _OCIE1A : 1; + uint8_t _OCIE1B : 1; + uint8_t reserved1 : 2; + uint8_t _ICIE1: 1; + uint8_t reserved2 : 2; + #endif + }; + static_assert(sizeof(TIMSK1_reg_t) == 1, "invalid size of ATmega2560 TIMSK1_reg_t"); + + struct TIMSK2_reg_t { + uint8_t _TOIE2 : 1; + uint8_t _OCIE2A : 1; + uint8_t _OCIE2B : 1; + uint8_t reserved1 : 5; + }; + static_assert(sizeof(TIMSK2_reg_t) == 1, "invalid size of ATmega2560 TIMSK2_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM03__ || __AVR_TRM04__ || __AVR_TRM05__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + + struct TIMSK3_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _TOIE3 : 1; + uint8_t _OCIE3A : 1; + uint8_t _OCIE3B : 1; + uint8_t _OCIE3C : 1; + uint8_t reserved1 : 1; + uint8_t _ICIE3 : 1; + uint8_t reserved2 : 2; + #elif defined(__AVR_TRM02__) + uint8_t _TOIE3 : 1; + uint8_t _OCIE3A : 1; + uint8_t _OCIE3B : 1; + uint8_t reserved1 : 2; + uint8_t _ICIE3 : 1; + uint8_t reserved2 : 2; + #endif + }; + static_assert(sizeof(TIMSK3_reg_t) == 1, "invalid size of ATmega2560 TIMSK3_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM04__ + +#ifdef __AVR_TRM01__ + + struct TIMSK4_reg_t { + uint8_t _TOIE4 : 1; + uint8_t _OCIE4A : 1; + uint8_t _OCIE4B : 1; + uint8_t _OCIE4C : 1; + uint8_t reserved1 : 1; + uint8_t _ICIE4 : 1; + uint8_t reserved2 : 2; + }; + static_assert(sizeof(TIMSK4_reg_t) == 1, "invalid size of ATmega2560 TIMSK4_reg_t"); + + struct TIMSK5_reg_t { + uint8_t _TOIE5 : 1; + uint8_t _OCIE5A : 1; + uint8_t _OCIE5B : 1; + uint8_t _OCIE5C : 1; + uint8_t reserved1 : 1; + uint8_t _ICIE5 : 1; + uint8_t reserved2 : 2; + }; + static_assert(sizeof(TIMSK5_reg_t) == 1, "invalid size of ATmega2560 TIMSK5_reg_t"); + +#endif // __AVR_TRM01__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + + struct XMCRA_reg_t { + uint8_t _SRW0 : 2; + uint8_t _SRW1 : 2; + uint8_t _SRL : 3; + uint8_t _SRE : 1; + }; + static_assert(sizeof(XMCRA_reg_t) == 1, "invalid size of ATmega2560 XMCRA_reg_t"); + + struct XMCRB_reg_t { + uint8_t _XMM : 3; + uint8_t reserved1 : 4; + uint8_t _XMBK : 1; + }; + static_assert(sizeof(XMCRB_reg_t) == 1, "invalid size of ATmega2560 XMCRB_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM04__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + struct ADCSRA_reg_t { + uint8_t _ADPS : 3; + uint8_t _ADIE : 1; + uint8_t _ADIF : 1; + uint8_t _ADATE : 1; + uint8_t _ADSC : 1; + uint8_t _ADEN : 1; + }; + static_assert(sizeof(ADCSRA_reg_t) == 1, "invalid size of ATmega2560 ADCSRA_reg_t"); + + struct ADCSRB_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _ADTS : 3; + uint8_t _MUX5 : 1; + uint8_t reserved1 : 2; + uint8_t _ACME : 1; + uint8_t reserved2 : 1; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + uint8_t _ADTS : 3; + uint8_t reserved1 : 3; + uint8_t _ACME : 1; + uint8_t reserved2 : 1; + #endif + }; + static_assert(sizeof(ADCSRB_reg_t) == 1, "invalid size of ATmega2560 ADCSRB_reg_t"); + + struct ADMUX_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + uint8_t _MUX0 : 1; + uint8_t _MUX1 : 1; + uint8_t _MUX2 : 1; + uint8_t _MUX3 : 1; + uint8_t _MUX4 : 1; + uint8_t _ADLAR : 1; + uint8_t _REFS0 : 1; + uint8_t _REFS1 : 1; + #elif defined(__AVR_TRM03__) + uint8_t _MUX0 : 1; + uint8_t _MUX1 : 1; + uint8_t _MUX2 : 1; + uint8_t _MUX3 : 1; + uint8_t reserved1 : 1; + uint8_t _ADLAR : 1; + uint8_t _REFS0 : 1; + uint8_t _REFS1 : 1; + #endif + }; + static_assert(sizeof(ADMUX_reg_t) == 1, "invalid size of ATmega2560 ADMUX_reg_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM03__ || __AVR_TRM04__ + +#ifdef __AVR_TRM01__ + + struct DIDR2_reg_t { + uint8_t _ADC8D : 1; + uint8_t _ADC9D : 1; + uint8_t _ADC10D : 1; + uint8_t _ADC11D : 1; + uint8_t _ADC12D : 1; + uint8_t _ADC13D : 1; + uint8_t _ADC14D : 1; + uint8_t _ADC15D : 1; + }; + static_assert(sizeof(DIDR2_reg_t) == 1, "invalid size of ATmega2560 DIDR2_reg_t"); + +#endif // __AVR_TRM01__ + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + + struct DIDR0_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + uint8_t _ADC0D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC5D : 1; + uint8_t _ADC6D : 1; + uint8_t _ADC7D : 1; + #elif defined(__AVR_TRM03__) + uint8_t _ADC0D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC5D : 1; + uint8_t reserved1 : 2; + #endif + }; + static_assert(sizeof(DIDR0_reg_t) == 1, "invalid size of ATmega2560 DIDR0_reg_t"); + + struct DIDR1_reg_t { + uint8_t _AIN0D : 1; + uint8_t _AIN1D : 1; + uint8_t reserved1 : 6; + }; + static_assert(sizeof(DIDR1_reg_t) == 1, "invalid size of ATmega2560 DIDR1_reg_t"); + + struct TCCRnA_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t _WGMn0 : 1; + uint8_t _WGMn1 : 1; + uint8_t _COMnC : 2; + uint8_t _COMnB : 2; + uint8_t _COMnA : 2; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + uint8_t _WGMn0 : 1; + uint8_t _WGMn1 : 1; + uint8_t reserved1 : 2; + uint8_t _COMnB : 2; + uint8_t _COMnA : 2; + #endif + }; + static_assert(sizeof(TCCRnA_reg_t) == 1, "invalid size of ATmega2560 TCCRnA_reg_t"); + + struct TCCRnB_reg_t { + uint8_t _CSn : 3; + uint8_t _WGMn2 : 1; + uint8_t _WGMn3 : 1; + uint8_t reserved1 : 1; + uint8_t _ICESn : 1; + uint8_t _ICNCn : 1; + }; + static_assert(sizeof(TCCRnB_reg_t) == 1, "invalid size of ATmega2560 TCCRnB_reg_t"); + + struct TCCRnC_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint8_t reserved1 : 5; + uint8_t _FOCnC : 1; + uint8_t _FOCnB : 1; + uint8_t _FOCnA : 1; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + uint8_t reserved1 : 6; + uint8_t _FOCnB : 1; + uint8_t _FOCnA : 1; + #endif + }; + static_assert(sizeof(TCCRnC_reg_t) == 1, "invalid size of ATmega2560 TCCRnC_reg_t"); + + struct TIMER_dev_t { + TCCRnA_reg_t _TCCRnA; + TCCRnB_reg_t _TCCRnB; + TCCRnC_reg_t _TCCRnC; + uint8_t reserved1; + uint16_t _TCNTn; + uint16_t _ICRn; + uint16_t _OCRnA; + uint16_t _OCRnB; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + uint16_t _OCRnC; + #endif + + inline void operator = ( const TIMER_dev_t& r ) volatile { + using namespace AVRHelpers; + dwrite(this->_TCCRnA, r._TCCRnA); + dwrite(this->_TCCRnB, r._TCCRnB); + dwrite(this->_TCCRnC, r._TCCRnC); + this->reserved1 = r.reserved1; + this->_TCNTn = r._TCNTn; + this->_ICRn = r._ICRn; + this->_OCRnA = r._OCRnA; + this->_OCRnB = r._OCRnB; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + this->_OCRnC = r._OCRnC; + #endif + } + }; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + static_assert(sizeof(TIMER_dev_t) == 14, "invalid size of ATmega2560 TIMER_dev_t"); + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + static_assert(sizeof(TIMER_dev_t) == 12, "invalid size of ATmega1284 TIMER_dev_t"); + #endif + + struct TCCRnA_8bit_reg_t { + uint8_t _WGMn0 : 1; + uint8_t _WGMn1 : 1; + uint8_t reserved1 : 2; + uint8_t _COMnB : 2; + uint8_t _COMnA : 2; + }; + static_assert(sizeof(TCCRnA_8bit_reg_t) == 1, "invalid size of ATmega2560 TCCRnA_8bit_reg_t"); + + struct TCCRnB_8bit_reg_t { + uint8_t _CSn : 3; + uint8_t _WGMn2 : 1; + uint8_t reserved1 : 2; + uint8_t _FOCnB : 1; + uint8_t _FOCnA : 1; + }; + static_assert(sizeof(TCCRnB_8bit_reg_t) == 1, "invalid size of ATmega2560 TCCRnB_8bit_reg_t"); + + struct TIMER_8bit_dev_t { + TCCRnA_8bit_reg_t _TCCRnA; + TCCRnB_8bit_reg_t _TCCRnB; + uint8_t _TCNTn; + uint8_t _OCRnA; + uint8_t _OCRnB; + + inline void operator = ( const TIMER_8bit_dev_t& r ) volatile { + using namespace AVRHelpers; + dwrite(this->_TCCRnA, r._TCCRnA); + dwrite(this->_TCCRnB, r._TCCRnB); + this->_TCNTn = r._TCNTn; + this->_OCRnA = r._OCRnA; + this->_OCRnB = r._OCRnB; + } + }; + static_assert(sizeof(TIMER_8bit_dev_t) == 5, "invalid size of ATmega2560 TIMER_8bit_dev_t"); + + struct ASSR_reg_t { + uint8_t _TCR2BUB : 1; + uint8_t _TCR2AUB : 1; + uint8_t _OCR2BUB : 1; + uint8_t _OCR2AUB : 1; + uint8_t _TCN2UB : 1; + uint8_t _AS2 : 1; + uint8_t _EXCLK : 1; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(ASSR_reg_t) == 1, "invalid size of ATmega2560 ASSR_reg_t"); + + struct TWSR_reg_t { + uint8_t _TWPS0 : 1; + uint8_t _TWPS1 : 1; + uint8_t reserved1 : 1; + uint8_t _TWS3 : 1; + uint8_t _TWS4 : 1; + uint8_t _TWS5 : 1; + uint8_t _TWS6 : 1; + uint8_t _TWS7 : 1; + }; + static_assert(sizeof(TWSR_reg_t) == 1, "invalid size of ATmega2560 TWSR_reg_t"); + + struct TWAR_reg_t { + uint8_t _TWGCE : 1; + uint8_t _TWA : 7; + }; + static_assert(sizeof(TWAR_reg_t) == 1, "invalid size of ATmega2560 TWAR_reg_t"); + + struct TWCR_reg_t { + uint8_t _TWIE : 1; + uint8_t reserved1 : 1; + uint8_t _TWEN : 1; + uint8_t _TWWC : 1; + uint8_t _TWSTO : 1; + uint8_t _TWSTA : 1; + uint8_t _TWEA : 1; + uint8_t _TWINT : 1; + }; + static_assert(sizeof(TWCR_reg_t) == 1, "invalid size of ATmega2560 TWCR_reg_t"); + + struct TWAMR_reg_t { + uint8_t reserved1 : 1; + uint8_t _TWAM : 7; + }; + static_assert(sizeof(TWAMR_reg_t) == 1, "invalid size of ATmega2560 TWAMR_reg_t"); + + struct UBRRn_reg_t { + uint16_t _UBRR : 12; + uint16_t reserved1 : 4; + }; + static_assert(sizeof(UBRRn_reg_t) == 2, "invalid size of ATmega2560 UBRRn_reg_t)"); + + struct UCSRnC_reg_t { + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + uint8_t _UCPOL : 1; + uint8_t _UCSZn0 : 1; + uint8_t _UCSZn1 : 1; + uint8_t _USBS : 1; + uint8_t _UPM : 2; + uint8_t _UMSEL : 2; + #elif defined(__AVR_TRM05__) + uint8_t _UCPOL : 1; + uint8_t _UCPHA : 1; + uint8_t _UDORD : 1; + uint8_t reserved1 : 3; + uint8_t _UMSEL : 2; + #endif + }; + static_assert(sizeof(UCSRnC_reg_t) == 1, "invalid size of ATmega2560 UCSRnC_reg_t"); + + struct UCSRnB_reg_t { + uint8_t _TXB8 : 1; + uint8_t _RXB8 : 1; + uint8_t _UCSZn2 : 1; + uint8_t _TXEN : 1; + uint8_t _RXEN : 1; + uint8_t _UDRIE : 1; + uint8_t _TXCIE : 1; + uint8_t _RXCIE : 1; + }; + static_assert(sizeof(UCSRnB_reg_t) == 1, "invalid size of ATmega2560 UCSRnB_reg_t"); + + struct UCSRnA_reg_t { + uint8_t _MPCM : 1; + uint8_t _U2X : 1; + uint8_t _UPE : 1; + uint8_t _DOR : 1; + uint8_t _FE : 1; + uint8_t _UDRE : 1; + uint8_t _TXC : 1; + uint8_t _RXC : 1; + }; + static_assert(sizeof(UCSRnA_reg_t) == 1, "invalid size of ATmega2560 UCSRnA_reg_t"); + + struct USART_dev_t { + UCSRnA_reg_t _UCSRnA; + UCSRnB_reg_t _UCSRnB; + UCSRnC_reg_t _UCSRnC; + uint8_t reserved1; + UBRRn_reg_t _UBRRn; + uint8_t _UDRn; + + inline void operator = ( const USART_dev_t& r ) volatile { + using namespace AVRHelpers; + dwrite(this->_UCSRnA, r._UCSRnA); + dwrite(this->_UCSRnB, r._UCSRnB); + dwrite(this->_UCSRnC, r._UCSRnC); + dwrite(this->reserved1, r.reserved1); + dwrite(this->_UBRRn, r._UBRRn); + dwrite(this->_UDRn, r._UDRn); + } + }; + static_assert(sizeof(USART_dev_t) == 7, "invalid size of ATmega2560 USART_dev_t"); + +#endif // __AVR_TRM01__ || __AVR_TRM02__ || __AVR_TRM03__ || __AVR_TRM04__ + +#ifdef __AVR_TRM04__ + + struct UHCON_reg_t { + uint8_t _SOFEN : 1; + uint8_t _RESET : 1; + uint8_t _RESUME : 1; + uint8_t reserved1 : 5; + }; + static_assert(sizeof(UHCON_reg_t) == 1, "invalid size of ATUSB90 UHCON_reg_t"); + + struct UHINT_reg_t { + uint8_t _DCONNI : 1; + uint8_t _DDISCI : 1; + uint8_t _RSTI : 1; + uint8_t _RSMEDI : 1; + uint8_t _RXRSMI : 1; + uint8_t _HSOFI : 1; + uint8_t _HWUPI : 1; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UHINT_reg_t) == 1, "invalid size of ATUSB90 UHINT_reg_t"); + + struct UHIEN_reg_t { + uint8_t _SUSPE : 1; + uint8_t _MSOFE : 1; + uint8_t _SOFE : 1; + uint8_t _EORSTE : 1; + uint8_t _WAKEUPE : 1; + uint8_t _EORSME : 1; + uint8_t _UPRSME : 1; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UHIEN_reg_t) == 1, "invalid size of ATUSB90 UHIEN_reg_t"); + + struct UHADDR_reg_t { + uint8_t _HADD : 7; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UHADDR_reg_t) == 1, "invalid size of ATUSB90 UHADDR_reg_t"); + + struct UHFNUM_reg_t { + uint16_t _FNUM : 11; + uint16_t reserved1 : 5; + }; + static_assert(sizeof(UHFNUM_reg_t) == 2, "invalid size of ATUSB90 UHFNUM_reg_t"); + + struct UPINTX_reg_t { + uint8_t _RXINI : 1; + uint8_t _RXSTALLI : 1; + uint8_t _TXOUTI : 1; + uint8_t _TXSTPI : 1; + uint8_t _PERRI : 1; + uint8_t _RWAL : 1; + uint8_t _NAKEDI : 1; + uint8_t _FIFOCON : 1; + }; + static_assert(sizeof(UPINTX_reg_t) == 1, "invalid size of ATUSB90 UPINTX_reg_t"); + + struct UPNUM_reg_t { + uint8_t _PNUM : 3; + uint8_t reserved1 : 5; + }; + static_assert(sizeof(UPNUM_reg_t) == 1, "invalid size of ATUSB90 UPNUM_reg_t"); + + struct UPRST_reg_t { + uint8_t _PRST : 7; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UPRST_reg_t) == 1, "invalid size of ATUSB90 UPRST_reg_t"); + + struct UPCONX_reg_t { + uint8_t _PEN : 1; + uint8_t reserved1 : 2; + uint8_t _RSTDT : 1; + uint8_t _AUTOSW : 1; + uint8_t _INMODE : 1; + uint8_t _PFREEZE : 1; + uint8_t reserved2 : 1; + }; + static_assert(sizeof(UPCONX_reg_t) == 1, "invalid size of ATUSB90 UPCONX_reg_t"); + + struct UPCFG0X_reg_t { + uint8_t _PEPNUM : 4; + uint8_t _PTOKEN : 2; + uint8_t _PTYPE : 2; + }; + static_assert(sizeof(UPCFG0X_reg_t) == 1, "invalid size of ATUSB90 UPCFG0_reg_t"); + + struct UPCFG1X_reg_t { + uint8_t reserved1 : 1; + uint8_t _ALLOC : 1; + uint8_t _PBK : 2; + uint8_t _PSIZE : 3; + uint8_t reserved2 : 1; + }; + static_assert(sizeof(UPCFG1X_reg_t) == 1, "invalid size of ATUSB90 UPCFG1X_reg_t"); + + struct UPSTAX_reg_t { + uint8_t _NBUSYBK : 2; + uint8_t _DTSEQ : 2; + uint8_t reserved1 : 1; + uint8_t _UNDERFI : 1; + uint8_t _OVERFI : 1; + uint8_t _CFGOK : 1; + }; + static_assert(sizeof(UPSTAX_reg_t) == 1, "invalid size of ATUSB90 UPSTAX_reg_t"); + + struct UPIENX_reg_t { + uint8_t _RXINE : 1; + uint8_t _RXSTALLE : 1; + uint8_t _TXOUTE : 1; + uint8_t _TXSTPE : 1; + uint8_t _PERRE : 1; + uint8_t reserved1 : 1; + uint8_t _NAKEDE : 1; + uint8_t _FLERRE : 1; + }; + static_assert(sizeof(UPIENX_reg_t) == 1, "invalid size of ATUSB90 UPIENX_reg_t"); + + struct UHWCON_reg_t { + uint8_t _UVREGE : 1; + uint8_t reserved1 : 3; + uint8_t _UVCONE : 1; + uint8_t reserved2 : 1; + uint8_t _UIDE : 1; + uint8_t _UIMOD : 1; + }; + static_assert(sizeof(UHWCON_reg_t) == 1, "invalid size of ATUSB90 UHWCON_reg_t"); + + struct USBCON_reg_t { + uint8_t _VBUSTE : 1; + uint8_t _IDTE : 1; + uint8_t reserved1 : 2; + uint8_t _OTGPADE : 1; + uint8_t _FRZCLK : 1; + uint8_t _HOST : 1; + uint8_t _USBE : 1; + }; + static_assert(sizeof(USBCON_reg_t) == 1, "invalid size of ATUSB90 USBCON_reg_t"); + + struct USBSTA_reg_t { + uint8_t _VBUS : 1; + uint8_t _ID : 1; + uint8_t reserved1 : 1; + uint8_t _SPEED : 1; + uint8_t reserved2 : 4; + }; + static_assert(sizeof(USBSTA_reg_t) == 1, "invalid size of ATUSB90 USBSTA_reg_t"); + + struct USBINT_reg_t { + uint8_t _VBUSTI : 1; + uint8_t _IDTI : 1; + uint8_t reserved1 : 6; + }; + static_assert(sizeof(USBINT_reg_t) == 1, "invalid size of ATUSB90 USBINT_reg_t"); + + struct UDPADD_reg_t { + uint16_t _DPADD : 11; + uint16_t reserved1 : 4; + uint16_t _DPACC : 1; + }; + static_assert(sizeof(UDPADD_reg_t) == 2, "invalid size of ATUSB90 UDPADD_reg_t"); + + struct OTGCON_reg_t { + uint8_t _VBUSRQC : 1; + uint8_t _VBUSREQ : 1; + uint8_t _VBUSHWC : 1; + uint8_t _SRPSEL : 1; + uint8_t _SRPREQ : 1; + uint8_t _HNPREQ : 1; + uint8_t reserved1 : 1; + uint8_t _zero : 1; + }; + static_assert(sizeof(OTGCON_reg_t) == 1, "invalid size of ATUSB90 OTGCON_reg_t"); + + struct OTGIEN_reg_t { + uint8_t _SRPE : 1; + uint8_t _VBERRE : 1; + uint8_t _BCERRE : 1; + uint8_t _ROLEEXE : 1; + uint8_t _HNPERRE : 1; + uint8_t _STOE : 1; + uint8_t reserved1 : 2; + }; + static_assert(sizeof(OTGIEN_reg_t) == 1, "invalid size of ATUSB90 OTGIEN_reg_t"); + + struct OTGINT_reg_t { + uint8_t _SRPI : 1; + uint8_t _VBERRI : 1; + uint8_t _BCERRI : 1; + uint8_t _ROLEEXI : 1; + uint8_t _HNPERRI : 1; + uint8_t _STOI : 1; + uint8_t reserved1 : 2; + }; + static_assert(sizeof(OTGINT_reg_t) == 1, "invalid size of ATUSB90 OTGINT_reg_t"); + + struct UDCON_reg_t { + uint8_t _DETACH : 1; + uint8_t _RMWKUP : 1; + uint8_t _LSM : 1; + uint8_t reserved1 : 5; + }; + static_assert(sizeof(UDCON_reg_t) == 1, "invalid size of ATUSB90 UDCON_reg_t"); + + struct UDINT_reg_t { + uint8_t _SUSPI : 1; + uint8_t _MSOFI : 1; + uint8_t _SOFI : 1; + uint8_t _EORSTI : 1; + uint8_t _WAKEUPI : 1; + uint8_t _EORSMI : 1; + uint8_t _UPRSMI : 1; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UDINT_reg_t) == 1, "invalid size of ATUSB90 UDINT_reg_t"); + + struct UDIEN_reg_t { + uint8_t _SUSPE : 1; + uint8_t _MSOFE : 1; + uint8_t _SOFE : 1; + uint8_t _EORSTE : 1; + uint8_t _WAKEUPE : 1; + uint8_t _EORSME : 1; + uint8_t _UPRSME : 1; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UDIEN_reg_t) == 1, "invalid size of ATUSB90 UDIEN_reg_t"); + + struct UDADDR_reg_t { + uint8_t _UADD : 7; + uint8_t _ADDEN : 1; + }; + static_assert(sizeof(UDADDR_reg_t) == 1, "invalid size of ATUSB90 UADDR_reg_t"); + + struct UDFNUM_reg_t { + uint16_t _FNUM : 11; + uint16_t reserved1 : 5; + }; + static_assert(sizeof(UDFNUM_reg_t) == 2, "invalid size of ATUSB90 UDFNUM_reg_t"); + + struct UDMFN_reg_t { + uint8_t reserved1 : 4; + uint8_t _FNCERR : 1; + uint8_t reserved2 : 3; + }; + static_assert(sizeof(UDMFN_reg_t) == 1, "invalid size of ATUSB90 UDMFN_reg_t"); + + struct UDTST_reg_t { + uint8_t reserved1 : 2; + uint8_t _TSTJ : 1; + uint8_t _TSTK : 1; + uint8_t _TSTPCKT : 1; + uint8_t _OPMODE2 : 1; + uint8_t reserved2 : 2; + }; + static_assert(sizeof(UDTST_reg_t) == 1, "invalid size of ATUSB90 UDTST_reg_t"); + + struct UEINTX_reg_t { + uint8_t _TXINI : 1; + uint8_t _STALLEDI : 1; + uint8_t _RXOUTI : 1; + uint8_t _RXSTPI : 1; + uint8_t _NAKOUTI : 1; + uint8_t _RWAL : 1; + uint8_t _NAKINI : 1; + uint8_t _FIFOCON : 1; + }; + static_assert(sizeof(UEINTX_reg_t) == 1, "invalid size of ATUSB90 UEINTX_reg_t"); + + struct UENUM_reg_t { + uint8_t _EPNUM : 3; + uint8_t reserved1 : 5; + }; + static_assert(sizeof(UENUM_reg_t) == 1, "invalid size of ATUSB90 UENUM_reg_t"); + + struct UERST_reg_t { + uint8_t _EPRST : 7; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UERST_reg_t) == 1, "invalid size of ATUSB90 UERST_reg_t"); + + struct UECONX_reg_t { + uint8_t _EPEN : 1; + uint8_t reserved1 : 2; + uint8_t _RSTDT : 1; + uint8_t _STALLRQC : 1; + uint8_t _STALLRQ : 1; + uint8_t reserved2 : 2; + }; + static_assert(sizeof(UECONX_reg_t) == 1, "invalid size of ATUSB90 UECONX_reg_t"); + + struct UECFG0X_reg_t { + uint8_t _EPDIR : 1; + uint8_t _NYETSDIS : 1; + uint8_t _AUTOSW : 1; + uint8_t _ISOSW : 1; + uint8_t reserved1 : 2; + uint8_t _EPTYPE : 2; + }; + static_assert(sizeof(UECFG0X_reg_t) == 1, "invalid size of ATUSB90 UECFG0X_reg_t"); + + struct UECFG1X_reg_t { + uint8_t reserved1 : 1; + uint8_t _ALLOC : 1; + uint8_t _EPBK : 2; + uint8_t _EPSIZE : 3; + uint8_t reserved2 : 1; + }; + static_assert(sizeof(UECFG1X_reg_t) == 1, "invalid size of ATUSB90 UECFG1X_reg_t"); + + struct UESTA0X_reg_t { + uint8_t _NBUSYBK : 2; + uint8_t _DTSEQ : 2; + uint8_t _ZLPSEEN : 1; + uint8_t _UNDERFI : 1; + uint8_t _OVERFI : 1; + uint8_t _CFGOK : 1; + }; + static_assert(sizeof(UESTA0X_reg_t) == 1, "invalid size of ATUSB90 UESTA0X_reg_t"); + + struct UESTA1X_reg_t { + uint8_t _CURRBK : 2; + uint8_t _CTRLDIR : 1; + uint8_t reserved1 : 5; + }; + static_assert(sizeof(UESTA1X_reg_t) == 1, "invalid size of ATUSB90 UESTA1X_reg_t"); + + struct UEIENX_reg_t { + uint8_t _TXINE : 1; + uint8_t _STALLEDE : 1; + uint8_t _RXOUTE : 1; + uint8_t _RXSTPE : 1; + uint8_t _NAKOUTE : 1; + uint8_t reserved1 : 1; + uint8_t _NAKINE : 1; + uint8_t _FLERRE : 1; + }; + static_assert(sizeof(UEIENX_reg_t) == 1, "invalid size of ATUSB90 UEIENX_reg_t"); + + struct UEBCX_reg_t { + uint16_t _BYCT : 11; + uint16_t reserved1 : 5; + }; + static_assert(sizeof(UEBCX_reg_t) == 2, "invalid size of ATUSB90 UEBCX_reg_t"); + + struct UEINT_reg_t { + uint8_t _EPINT : 7; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UEINT_reg_t) == 1, "invalid size of ATUSB90 UEINT_reg_t"); + + struct UPERRX_reg_t { + uint8_t _DATATGL : 1; + uint8_t _DATAPID : 1; + uint8_t _PID : 1; + uint8_t _TIMEOUT : 1; + uint8_t _CRC16 : 1; + uint8_t _COUNTER : 2; + uint8_t reserved1 : 1; + }; + static_assert(sizeof(UPERRX_reg_t) == 1, "invalid size of ATUSB90 UPERRX_reg_t"); + + struct UPBCX_reg_t { + uint16_t _PBYCT : 11; + uint16_t reserved1 : 5; + }; + static_assert(sizeof(UPBCX_reg_t) == 2, "invalid size of ATUSB90 UPBCX_reg_t"); + + struct OTGTCON_reg_t { + uint8_t _VALUE : 2; + uint8_t reserved1 : 3; + uint8_t _PAGE : 2; + uint8_t _one : 1; + }; + static_assert(sizeof(OTGTCON_reg_t) == 1, "invalid size of ATUSB90 OTGTCON_reg_t"); + + struct PLLCSR_reg_t { + uint8_t _PLOCK : 1; + uint8_t _PLLE : 1; + uint8_t _PLLP : 3; + uint8_t reserved1 : 3; + }; + static_assert(sizeof(PLLCSR_reg_t) == 1, "invalid size of ATUSB90 PLLCSR_reg_t"); + +#endif // __AVR_TRM04__ + +/** + * REGISTER MEMORY MAP + */ + +#define __AVR_DEFREG(tn,n,a) static volatile tn& n = *(tn*)a +#define _AVR_DEFREG(n,a) __AVR_DEFREG(n##_reg_t, _##n, a) + +#ifdef __AVR_TRM01__ + // page 399ff of ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf + + __AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); + __AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); + __AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); + __AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); + __AVR_DEFREG(PORT_dev_t, _PORTE, 0x2C); + __AVR_DEFREG(PORT_dev_t, _PORTF, 0x2F); + __AVR_DEFREG(PORTG_dev_t, _PORTG, 0x32); + __AVR_DEFREG(PORT_dev_t, _PORTH, 0x100); + __AVR_DEFREG(PORT_dev_t, _PORTJ, 0x103); + __AVR_DEFREG(PORT_dev_t, _PORTK, 0x106); + __AVR_DEFREG(PORT_dev_t, _PORTL, 0x109); + __AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); + __AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); + __AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); + __AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); + __AVR_DEFREG(TIFR4_reg_t, _TIFR4, 0x39); + __AVR_DEFREG(TIFR5_reg_t, _TIFR5, 0x3A); + __AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); + __AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); + __AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); + __AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); + __AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); + __AVR_DEFREG(uint8_t, _EEDR, 0x40); + __AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); + __AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); + __AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); + __AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); + __AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); + __AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); + __AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); + __AVR_DEFREG(uint8_t, _SPDR, 0x4E); + __AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); + __AVR_DEFREG(_bit_reg_t, _OCDR, 0x51); + __AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); + __AVR_DEFREG(MCUSR_reg_t, _MCUSR, 0x54); + __AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); + __AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); + __AVR_DEFREG(RAMPZ_reg_t, _RAMPZ, 0x5B); + __AVR_DEFREG(EIND_reg_t, _EIND, 0x5C); + __AVR_DEFREG(SP_reg_t, _SP, 0x5D); + __AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); + __AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); + __AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); + __AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); + __AVR_DEFREG(PRR1_reg_t, _PRR1, 0x65); + __AVR_DEFREG(uint8_t, _OSCCAL, 0x66); + __AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); + __AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); + __AVR_DEFREG(EICRB_reg_t, _EICRB, 0x6A); + __AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); + __AVR_DEFREG(_bit_reg_t, _PCMSK1, 0x6C); + __AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); + __AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); + __AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); + __AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); + __AVR_DEFREG(TIMSK3_reg_t, _TIMSK3, 0x71); + __AVR_DEFREG(TIMSK4_reg_t, _TIMSK4, 0x72); + __AVR_DEFREG(TIMSK5_reg_t, _TIMSK5, 0x73); + __AVR_DEFREG(XMCRA_reg_t, _XMCRA, 0x74); + __AVR_DEFREG(XMCRB_reg_t, _XMCRB, 0x75); + __AVR_DEFREG(uint16_t, _ADC, 0x78); + __AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); + __AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); + __AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); + __AVR_DEFREG(DIDR2_reg_t, _DIDR2, 0x7D); + __AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); + __AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); + __AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); + __AVR_DEFREG(TIMER_dev_t, TIMER3, 0x90); + __AVR_DEFREG(TIMER_dev_t, TIMER4, 0xA0); + __AVR_DEFREG(TIMER_dev_t, TIMER5, 0x120); + __AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); + __AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); + __AVR_DEFREG(uint8_t, _TWBR, 0xB8); + __AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); + __AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); + __AVR_DEFREG(uint8_t, _TWDR, 0xBB); + __AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); + __AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); + __AVR_DEFREG(USART_dev_t, USART0, 0xC0); + __AVR_DEFREG(USART_dev_t, USART1, 0xC8); + __AVR_DEFREG(USART_dev_t, USART2, 0xD0); + __AVR_DEFREG(USART_dev_t, USART3, 0x130); + +#elif defined(__AVR_TRM02__) + // page 637ff of ATmega164A_PA-324A_PA-644A_PA-1284_P_Data-Sheet-40002070B.pdf + __AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); + __AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); + __AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); + __AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); + __AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); + __AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); + __AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); + __AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); + __AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); + __AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); + __AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); + __AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); + __AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); + __AVR_DEFREG(uint8_t, _EEDR, 0x40); + __AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); + __AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); + __AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); + __AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); + __AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); + __AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); + __AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); + __AVR_DEFREG(uint8_t, _SPDR, 0x4E); + __AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); + __AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); + __AVR_DEFREG(MCUSR_reg_t, _MSUSR, 0x54); + __AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); + __AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); + __AVR_DEFREG(SP_reg_t, _SP, 0x5D); + __AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); + __AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); + __AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); + __AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); + __AVR_DEFREG(PRR1_reg_t, _PRR1, 0x65); + __AVR_DEFREG(uint8_t, _OSCCAL, 0x66); + __AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); + __AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); + __AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); + __AVR_DEFREG(_bit_reg_t, _PCMSK1, 0x6C); + __AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); + __AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); + __AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); + __AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); + __AVR_DEFREG(TIMSK3_reg_t, _TIMSK3, 0x71); + __AVR_DEFREG(_bit_reg_t, _PCMSK3, 0x73); + __AVR_DEFREG(uint16_t, _ADC, 0x78); + __AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); + __AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); + __AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); + __AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); + __AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); + __AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); + __AVR_DEFREG(TIMER_dev_t, TIMER3, 0x90); + __AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); + __AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); + __AVR_DEFREG(uint8_t, _TWBR, 0xB8); + __AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); + __AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); + __AVR_DEFREG(uint8_t, _TWDR, 0xBB); + __AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); + __AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); + __AVR_DEFREG(USART_dev_t, USART0, 0xC0); + __AVR_DEFREG(USART_dev_t, USART1, 0xC8); + +#elif defined(__AVR_TRM03__) + // page 621ff of ATmega48A-PA-88A-PA-168A-PA-328-P-DS-DS40002061B.pdf + __AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); + __AVR_DEFREG(PORTC_dev_t, _PORTC, 0x26); + __AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); + __AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); + __AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); + __AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); + __AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); + __AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); + __AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); + __AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); + __AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); + __AVR_DEFREG(uint8_t, _EEDR, 0x40); + __AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); + __AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); + __AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); + __AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); + __AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); + __AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); + __AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); + __AVR_DEFREG(uint8_t, _SPDR, 0x4E); + __AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); + __AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); + __AVR_DEFREG(MCUSR_reg_t, _MSUCR, 0x54); + __AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); + __AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); + __AVR_DEFREG(SP_reg_t, _SP, 0x5D); + __AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); + __AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); + __AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); + __AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); + __AVR_DEFREG(uint8_t, _OSCCAL, 0x66); + __AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); + __AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); + __AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); + __AVR_DEFREG(_bitPCMSK1_reg_t, _PCMSK1, 0x6C); + __AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); + __AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); + __AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); + __AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); + __AVR_DEFREG(uint16_t, _ADC, 0x78); + __AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); + __AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); + __AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); + __AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); + __AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); + __AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); + __AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); + __AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); + __AVR_DEFREG(uint8_t, _TWBR, 0xB8); + __AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); + __AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); + __AVR_DEFREG(uint8_t, _TWDR, 0xBB); + __AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); + __AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); + __AVR_DEFREG(USART_dev_t, USART0, 0xC0); + +#elif defined(__AVR_TRM04__) + __AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); + __AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); + __AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); + __AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); + __AVR_DEFREG(PORT_dev_t, _PORTE, 0x2C); + __AVR_DEFREG(PORT_dev_t, _PORTF, 0x2F); + __AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); + __AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); + __AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); + __AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); + __AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); + __AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); + __AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); + __AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); + __AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); + __AVR_DEFREG(uint8_t, _EEDR, 0x40); + __AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); + __AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); + __AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); + __AVR_DEFREG(PLLCSR_reg_t, _PLLCSR, 0x49); + __AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); + __AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); + __AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); + __AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); + __AVR_DEFREG(uint8_t, _SPDR, 0x4E); + __AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); + __AVR_DEFREG(uint8_t, _OCDR, 0x51); + __AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); + __AVR_DEFREG(MCUSR_reg_t, _MCUSR, 0x54); + __AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); + __AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); + __AVR_DEFREG(RAMPZ_reg_t, _RAMPZ, 0x5B); + __AVR_DEFREG(SP_reg_t, _SP, 0x5D); + __AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); + __AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); + __AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); + __AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); + __AVR_DEFREG(PRR1_reg_t, _PRR1, 0x65); + __AVR_DEFREG(uint8_t, _OSCCAL, 0x66); + __AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); + __AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); + __AVR_DEFREG(EICRB_reg_t, _EICRB, 0x6A); + __AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); + __AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); + __AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); + __AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); + __AVR_DEFREG(TIMSK3_reg_t, _TIMSK3, 0x71); + __AVR_DEFREG(XMCRA_reg_t, _XMCRA, 0x74); + __AVR_DEFREG(XMCRB_reg_t, _XMCRB, 0x75); + __AVR_DEFREG(uint16_t, _ADC, 0x78); + __AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); + __AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); + __AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); + __AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); + __AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); + __AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); + __AVR_DEFREG(TIMER_dev_t, TIMER3, 0x90); + __AVR_DEFREG(UHCON_reg_t, _UHCON, 0x9E); + __AVR_DEFREG(UHINT_reg_t, _UHINT, 0x9F); + __AVR_DEFREG(UHIEN_reg_t, _UHIEN, 0xA0); + __AVR_DEFREG(UHADDR_reg_t, _UHADDR, 0xA1); + __AVR_DEFREG(UHFNUM_reg_t, _UHFNUM, 0xA2); + __AVR_DEFREG(uint8_t, _UHFLEN, 0xA4); + __AVR_DEFREG(uint8_t, _UPINRQX, 0xA5); + __AVR_DEFREG(UPINTX_reg_t, _UPINTX, 0xA6); + __AVR_DEFREG(UPNUM_reg_t, _UPNUM, 0xA7); + __AVR_DEFREG(UPRST_reg_t, _UPRST, 0xA8); + __AVR_DEFREG(UPCONX_reg_t, _UPCONX, 0xA9); + _AVR_DEFREG(UPCFG0X, 0xAA); + _AVR_DEFREG(UPCFG1X, 0xAB); + _AVR_DEFREG(UPSTAX, 0xAC); + __AVR_DEFREG(uint8_t, _UPCFG2X, 0xAD); + _AVR_DEFREG(UPIENX, 0xAE); + __AVR_DEFREG(uint8_t, _UPDATX, 0xAF); + __AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); + __AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); + __AVR_DEFREG(uint8_t, _TWBR, 0xB8); + __AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); + __AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); + __AVR_DEFREG(uint8_t, _TWDR, 0xBB); + __AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); + __AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); + __AVR_DEFREG(USART_dev_t, USART1, 0xC8); + _AVR_DEFREG(UHWCON, 0xD7); + _AVR_DEFREG(USBCON, 0xD8); + _AVR_DEFREG(USBSTA, 0xD9); + _AVR_DEFREG(USBINT, 0xDA); + _AVR_DEFREG(UDPADD, 0xDB); + _AVR_DEFREG(OTGCON, 0xDD); + _AVR_DEFREG(OTGIEN, 0xDE); + _AVR_DEFREG(OTGINT, 0xDF); + _AVR_DEFREG(UDCON, 0xE0); + _AVR_DEFREG(UDINT, 0xE1); + _AVR_DEFREG(UDIEN, 0xE2); + _AVR_DEFREG(UDADDR, 0xE3); + _AVR_DEFREG(UDFNUM, 0xE4); + _AVR_DEFREG(UDMFN, 0xE6); + _AVR_DEFREG(UDTST, 0xE7); + _AVR_DEFREG(UEINTX, 0xE8); + _AVR_DEFREG(UENUM, 0xE9); + _AVR_DEFREG(UERST, 0xEA); + _AVR_DEFREG(UECONX, 0xEB); + _AVR_DEFREG(UECFG0X, 0xEC); + _AVR_DEFREG(UECFG1X, 0xED); + _AVR_DEFREG(UESTA0X, 0xEE); + _AVR_DEFREG(UESTA1X, 0xEF); + _AVR_DEFREG(UEIENX, 0xF0); + __AVR_DEFREG(uint8_t, _UEDATx, 0xF1); + _AVR_DEFREG(UEBCX, 0xF2); + _AVR_DEFREG(UEINT, 0xF4); + _AVR_DEFREG(UPERRX, 0xF5); + _AVR_DEFREG(UPBCX, 0xF6); + __AVR_DEFREG(uint8_t, _UPINT, 0xF8); + _AVR_DEFREG(OTGTCON, 0xF9); +#elif defined(__AVR_TRM05__) + // page 476ff. of ATmega164P-324P-644P-Data-Sheet-40002071A.pdf + __AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); + __AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); + __AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); + __AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); + __AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); + __AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); + __AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); + __AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); + __AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); + __AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); + __AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); + __AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); + __AVR_DEFREG(uint8_t, _EEDR, 0x40); + __AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); + __AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); + __AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); + __AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); + __AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); + __AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); + __AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); + __AVR_DEFREG(uint8_t, _SPDR, 0x4E); + __AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); + __AVR_DEFREG(uint8_t, _OCDR, 0x51); + __AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); + __AVR_DEFREG(MCUSR_reg_t, _MCUSR, 0x54); + __AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); + __AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); + __AVR_DEFREG(RAMPZ_reg_t, _RAMPZ, 0x5B); + __AVR_DEFREG(SP_reg_t, _SP, 0x5D); + __AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); + __AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); + __AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); + __AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); + __AVR_DEFREG(uint8_t, _OSCCAL, 0x66); + __AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); + __AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); + __AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); + __AVR_DEFREG(_bit_reg_t, _PCMSK1, 0x6C); + __AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); + __AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); + __AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); + __AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); + __AVR_DEFREG(_bit_reg_t, _PCMKS3, 0x73); + __AVR_DEFREG(uint16_t, _ADC, 0x78); + __AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); + __AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); + __AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); + __AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); + __AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); + __AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); + __AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); + __AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); + __AVR_DEFREG(uint8_t, _TWBR, 0xB8); + __AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB8); + __AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); + __AVR_DEFREG(uint8_t, _TWDR, 0xBB); + __AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); + __AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); + __AVR_DEFREG(USART_dev_t, USART0, 0xC0); + __AVR_DEFREG(USART_dev_t, USART1, 0xC8); +#endif + +inline void _ATmega_resetperipherals() { + using namespace AVRHelpers; + + // Due to BOOTLOADER or other board inconsistencies we could get launched into Marlin FW + // with configuration that does not match the reset state in the documentation. That is why + // we should clean-reset the entire device. + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + SREG_reg_t __SREG; + __SREG._C = false; + __SREG._Z = false; + __SREG._N = false; + __SREG._V = false; + __SREG._S = false; + __SREG._H = false; + __SREG._T = false; + __SREG._I = false; + dwrite(_SREG, __SREG); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + _RAMPZ._RAMPZ = 0; + #endif + #ifdef __AVR_TRM01__ + _EIND._EIND0 = false; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + _EEAR._EEAR = 0; + dwrite(_EEDR, (uint8_t)0U); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + EECR_reg_t __EECR; + __EECR._EERE = false; + __EECR._EEPE = false; + __EECR._EEMPE = false; + __EECR._EERIE = false; + __EECR._EEPM0 = 0; + __EECR._EEPM1 = 0; + __EECR.reserved1 = 0; + dwrite(_EECR, __EECR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + _GPIOR2.val = 0; + _GPIOR1.val = 0; + _GPIOR0.val = 0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + XMCRA_reg_t __XMCRA; + __XMCRA._SRW0 = 0; + __XMCRA._SRW1 = 0; + __XMCRA._SRL = 0; + __XMCRA._SRE = 0; + dwrite(_XMCRA, __XMCRA); + + XMCRB_reg_t __XMCRB; + __XMCRB._XMM = 0; + __XMCRB.reserved1 = 0; + __XMCRB._XMBK = false; + dwrite(_XMCRB, __XMCRB); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + SMCR_reg_t __SMCR; + __SMCR._SE = false; + __SMCR._SM = 0; + __SMCR.reserved1 = 0; + dwrite(_SMCR, __SMCR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + PRR0_reg_t __PRR0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) + __PRR0._PRADC = false; + __PRR0._PRUSART0 = false; + __PRR0._PRSPI = false; + __PRR0._PRTIM1 = false; + __PRR0.reserved1 = false; + __PRR0._PRTIM0 = false; + __PRR0._PRTIM2 = false; + __PRR0._PRTWI = false; + #elif defined(__AVR_TRM02__) + __PRR0._PRADC = false; + __PRR0._PRUSART0 = false; + __PRR0._PRSPI = false; + __PRR0._PRTIM1 = false; + __PRR0._PRUSART1 = false; + __PRR0._PRTIM0 = false; + __PRR0._PRTIM2 = false; + __PRR0._PRTWI = false; + #elif defined(__AVR_TRM04__) + __PRR0._PRADC = false; + __PRR0.reserved1 = false; + __PRR0._PRSPI = false; + __PRR0._PRTIM1 = false; + __PRR0.reserved2 = false; + __PRR0._PRTIM0 = false; + __PRR0._PRTIM2 = false; + __PRR0._PRTWI = false; + #endif + dwrite(_PRR0, __PRR0); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + PRR1_reg_t __PRR1; + #ifdef __AVR_TRM01__ + __PRR1._PRUSART1 = false; + __PRR1._PRUSART2 = false; + __PRR1._PRUSART3 = false; + __PRR1._PRTIM3 = false; + __PRR1._PRTIM4 = false; + __PRR1._PRTIM5 = false; + __PRR1.reserved1 = 0; + #elif defined(__AVR_TRM02__) + __PRR1._PRTIM3 = false; + __PRR1.reserved1 = 0; + #elif defined(__AVR_TRM04__) + __PRR1._PRUSART1 = false; + __PRR1.reserved1 = 0; + #endif + dwrite(_PRR1, __PRR1); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + WDTCSR_reg_t __WDTCSR; + __WDTCSR._WDP0 = 0; + __WDTCSR._WDP1 = 0; + __WDTCSR._WDP2 = 0; + __WDTCSR._WDE = false; + __WDTCSR._WDCE = false; + __WDTCSR._WDP3 = 0; + __WDTCSR._WDIE = false; + __WDTCSR._WDIF = false; + dwrite(_WDTCSR, __WDTCSR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + _MCUCR._PUD = false; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + PORT_dev_t __PORT; + __PORT._PIN.val = 0; + __PORT._DDR.val = 0; + __PORT._PORT.val = 0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + dwrite(_PORTA, __PORT); + dwrite(_PORTC, __PORT); + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + dwrite(_PORTB, __PORT); + dwrite(_PORTD, __PORT); + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + dwrite(_PORTE, __PORT); + dwrite(_PORTF, __PORT); + #endif + + #ifdef __AVR_TRM01__ + PORTG_dev_t __PORTG; + __PORTG._PIN.val = 0; + __PORTG._PIN.reserved1 = 0; + __PORTG._DDR.val = 0; + __PORTG._DDR.reserved1 = 0; + __PORTG._PORT.val = 0; + __PORTG._PORT.reserved1 = 0; + dwrite(_PORTG, __PORTG); + #endif + + #ifdef __AVR_TRM03__ + PORTC_dev_t __PORTC; + __PORTC._PIN.val = 0; + __PORTC._PIN.reserved1 = 0; + __PORTC._DDR.val = 0; + __PORTC._DDR.reserved1 = 0; + __PORTC._PORT.val = 0; + __PORTC._PORT.reserved1 = 0; + dwrite(_PORTC, __PORTC); + #endif + + #ifdef __AVR_TRM01__ + dwrite(_PORTH, __PORT); + dwrite(_PORTJ, __PORT); + dwrite(_PORTK, __PORT); + dwrite(_PORTL, __PORT); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + EICRA_reg_t __EICRA; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __EICRA._ISC0 = 0; + __EICRA._ISC1 = 0; + __EICRA._ISC2 = 0; + __EICRA._ISC3 = 0; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + __EICRA._ISC0 = 0; + __EICRA._ISC1 = 0; + __EICRA._ISC2 = 0; + __EICRA.reserved1 = 0; + #elif defined(__AVR_TRM03__) + __EICRA._ISC0 = 0; + __EICRA._ISC1 = 0; + __EICRA.reserved1 = 0; + #endif + dwrite(_EICRA, __EICRA); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + EICRB_reg_t __EICRB; + __EICRB._ISC4 = 0; + __EICRB._ISC5 = 0; + __EICRB._ISC6 = 0; + __EICRB._ISC7 = 0; + dwrite(_EICRB, __EICRB); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + EIMSK_reg_t __EIMSK; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __EIMSK._INT0 = false; + __EIMSK._INT1 = false; + __EIMSK._INT2 = false; + __EIMSK._INT3 = false; + __EIMSK._INT4 = false; + __EIMSK._INT5 = false; + __EIMSK._INT6 = false; + __EIMSK._INT7 = false; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + __EIMSK._INT0 = false; + __EIMSK._INT1 = false; + __EIMSK._INT2 = false; + __EIMSK.reserved1 = 0; + #elif defined(__AVR_TRM03__) + __EIMSK._INT0 = false; + __EIMSK._INT1 = false; + __EIMSK.reserved1 = 0; + #endif + dwrite(_EIMSK, __EIMSK); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + EIFR_reg_t __EIFR; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __EIFR._INTF0 = false; + __EIFR._INTF1 = false; + __EIFR._INTF2 = false; + __EIFR._INTF3 = false; + __EIFR._INTF4 = false; + __EIFR._INTF5 = false; + __EIFR._INTF6 = false; + __EIFR._INTF7 = false; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + __EIFR._INTF0 = false; + __EIFR._INTF1 = false; + __EIFR._INTF2 = false; + __EIFR.reserved1 = 0; + #elif defined(__AVR_TRM03__) + __EIFR._INTF0 = false; + __EIFR._INTF1 = false; + __EIFR.reserved1 = 0; + #endif + dwrite(_EIFR, __EIFR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + PCICR_reg_t __PCICR; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) + __PCICR._PCIE0 = false; + __PCICR._PCIE1 = false; + __PCICR._PCIE2 = false; + __PCICR.reserved1 = 0; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + __PCICR._PCIE0 = false; + __PCICR._PCIE1 = false; + __PCICR._PCIE2 = false; + __PCICR._PCIE3 = false; + __PCICR.reserved1 = 0; + #elif defined(__AVR_TRM04__) + __PCICR._PCIE0 = false; + __PCICR.reserved1 = 0; + #endif + dwrite(_PCICR, __PCICR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + PCIFR_reg_t __PCIFR; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) + __PCIFR._PCIF0 = false; + __PCIFR._PCIF1 = false; + __PCIFR._PCIF2 = false; + __PCIFR.reserved1 = 0; + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + __PCIFR._PCIF0 = false; + __PCIFR._PCIF1 = false; + __PCIFR._PCIF2 = false; + __PCIFR._PCIF3 = false; + __PCIFR.reserved1 = 0; + #elif defined(__AVR_TRM04__) + __PCIFR._PCIF0 = false; + __PCIFR.reserved1 = 0; + #endif + dwrite(_PCIFR, __PCIFR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + _PCMSK0.val = 0; + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + _PCMSK1.val = 0; + _PCMSK2.val = 0; + #endif + #if defined(__AVR_TRM03__) + _PCMSK1.reserved1 = 0; + #endif + #if defined(__AVR_TRM02__) + _PCMSK3.val = 0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + TIMER_8bit_dev_t __TIMER_8bit; + __TIMER_8bit._TCCRnA._WGMn0 = 0; + __TIMER_8bit._TCCRnA._WGMn1 = 0; + __TIMER_8bit._TCCRnA.reserved1 = 0; + __TIMER_8bit._TCCRnA._COMnB = 0; + __TIMER_8bit._TCCRnA._COMnA = 0; + __TIMER_8bit._TCCRnB._CSn = 0; + __TIMER_8bit._TCCRnB._WGMn2 = 0; + __TIMER_8bit._TCCRnB.reserved1 = 0; + __TIMER_8bit._TCCRnB._FOCnB = false; + __TIMER_8bit._TCCRnB._FOCnA = false, + __TIMER_8bit._TCNTn = 0; + __TIMER_8bit._OCRnA = 0; + __TIMER_8bit._OCRnB = 0; + dwrite(TIMER0, __TIMER_8bit); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + TIMSK0_reg_t __TIMSK0; + __TIMSK0._TOIE0 = false; + __TIMSK0._OCIE0A = false; + __TIMSK0._OCIE0B = false; + __TIMSK0.reserved1 = 0; + dwrite(_TIMSK0, __TIMSK0); + + TIFR0_reg_t __TIFR0; + __TIFR0._TOV0 = false; + __TIFR0._OCF0A = false; + __TIFR0._OCF0B = false; + __TIFR0.reserved1 = 0; + dwrite(_TIFR0, __TIFR0); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + TIMER_dev_t TIMER; + TIMER._TCCRnA._WGMn0 = 0; + TIMER._TCCRnA._WGMn1 = 0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + TIMER._TCCRnA._COMnC = 0; + #endif + TIMER._TCCRnA._COMnB = 0; + TIMER._TCCRnA._COMnA = 0; + TIMER._TCCRnB._CSn = 0; + TIMER._TCCRnB._WGMn2 = 0; + TIMER._TCCRnB.reserved1 = 0; + TIMER._TCCRnB._ICESn = 0; + TIMER._TCCRnB._ICNCn = 0; + TIMER._TCCRnC.reserved1 = 0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + TIMER._TCCRnC._FOCnC = false; + #endif + TIMER._TCCRnC._FOCnB = false; + TIMER._TCCRnC._FOCnA = false; + TIMER._TCNTn = 0; + TIMER._OCRnA = 0; + TIMER._OCRnB = 0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + TIMER._OCRnC = 0; + #endif + TIMER._ICRn = 0; + dwrite(TIMER1, TIMER); + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + dwrite(TIMER3, TIMER); + #endif + #ifdef __AVR_TRM01__ + dwrite(TIMER4, TIMER); + dwrite(TIMER5, TIMER); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + TIMSK1_reg_t __TIMSK1; + __TIMSK1._TOIE1 = false; + __TIMSK1._OCIE1A = false; + __TIMSK1._OCIE1B = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __TIMSK1._OCIE1C = false; + #endif + __TIMSK1.reserved1 = 0; + __TIMSK1._ICIE1 = false; + __TIMSK1.reserved2 = 0; + dwrite(_TIMSK1, __TIMSK1); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + TIMSK3_reg_t __TIMSK3; + __TIMSK3._TOIE3 = false; + __TIMSK3._OCIE3A = false; + __TIMSK3._OCIE3B = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __TIMSK3._OCIE3C = false; + #endif + __TIMSK3.reserved1 = 0; + __TIMSK3._ICIE3 = false; + __TIMSK3.reserved2 = 0; + dwrite(_TIMSK3, __TIMSK3); + #endif + + #ifdef __AVR_TRM01__ + TIMSK4_reg_t __TIMSK4; + __TIMSK4._TOIE4 = false; + __TIMSK4._OCIE4A = false; + __TIMSK4._OCIE4B = false; + __TIMSK4._OCIE4C = false; + __TIMSK4.reserved1 = false; + __TIMSK4._ICIE4 = false; + __TIMSK4.reserved2 = false; + dwrite(_TIMSK4, __TIMSK4); + + TIMSK5_reg_t __TIMSK5; + __TIMSK5._TOIE5 = false; + __TIMSK5._OCIE5A = false; + __TIMSK5._OCIE5B = false; + __TIMSK5._OCIE5C = false; + __TIMSK5.reserved1 = 0; + __TIMSK5._ICIE5 = false; + __TIMSK5.reserved2 = 0; + dwrite(_TIMSK5, __TIMSK5); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + TIFR1_reg_t __TIFR1; + __TIFR1._TOV1 = false; + __TIFR1._OCF1A = false; + __TIFR1._OCF1B = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __TIFR1._OCF1C = false; + #endif + __TIFR1.reserved1 = 0; + __TIFR1._ICF1 = false; + __TIFR1.reserved2 = 0; + dwrite(_TIFR1, __TIFR1); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + TIFR3_reg_t __TIFR3; + __TIFR3._TOV3 = false; + __TIFR3._OCF3A = false; + __TIFR3._OCF3B = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __TIFR3._OCF3C = false; + #endif + __TIFR3.reserved1 = 0; + __TIFR3._ICF3 = false; + __TIFR3.reserved2 = 0; + dwrite(_TIFR3, __TIFR3); + #endif + + #ifdef __AVR_TRM01__ + TIFR4_reg_t __TIFR4; + __TIFR4._TOV4 = false; + __TIFR4._OCF4A = false; + __TIFR4._OCF4B = false; + __TIFR4._OCF4C = false; + __TIFR4.reserved1 = 0; + __TIFR4._ICF4 = false; + __TIFR4.reserved2 = 0; + dwrite(_TIFR4, __TIFR4); + + TIFR5_reg_t __TIFR5; + __TIFR5._TOV5 = false; + __TIFR5._OCF5A = false; + __TIFR5._OCF5B = false; + __TIFR5._OCF5C = false; + __TIFR5.reserved1 = 0; + __TIFR5._ICF5 = false; + __TIFR5.reserved2 = 0; + dwrite(_TIFR5, __TIFR5); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + dwrite(_TIMER2, __TIMER_8bit); + #endif + + #if defined(__AV_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + ASSR_reg_t __ASSR; + __ASSR._TCR2BUB = false; + __ASSR._TCR2AUB = false; + __ASSR._OCR2BUB = false; + __ASSR._OCR2AUB = false; + __ASSR._TCN2UB = false; + __ASSR._AS2 = false; + __ASSR._EXCLK = false; + __ASSR.reserved1 = 0; + dwrite(_ASSR, __ASSR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + TIMSK2_reg_t __TIMSK2; + __TIMSK2._TOIE2 = false; + __TIMSK2._OCIE2A = false; + __TIMSK2._OCIE2B = false; + __TIMSK2.reserved1 = 0; + dwrite(_TIMSK2, __TIMSK2); + + TIFR2_reg_t __TIFR2; + __TIFR2._TOV2 = false; + __TIFR2._OCF2A = false; + __TIFR2._OCF2B = false; + __TIFR2.reserved1 = 0; + dwrite(_TIFR2, __TIFR2); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + SPCR_reg_t __SPCR; + __SPCR._SPR = 0; + __SPCR._CPHA = 0; + __SPCR._CPOL = 0; + __SPCR._MSTR = 0; + __SPCR._DORD = 0; + __SPCR._SPE = false; + __SPCR._SPIE = false; + dwrite(_SPCR, __SPCR); + + SPSR_reg_t __SPSR; + __SPSR._SPI2X = false; + __SPSR.reserved1 = 0; + __SPSR._WCOL = false; + __SPSR._SPIF = false; + dwrite(_SPSR, __SPSR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + USART_dev_t USART; + USART._UDRn = 0; + USART._UCSRnA._MPCM = false; + USART._UCSRnA._U2X = false; + USART._UCSRnA._UPE = false; + USART._UCSRnA._DOR = false; + USART._UCSRnA._FE = false; + USART._UCSRnA._UDRE = true; + USART._UCSRnA._TXC = false; + USART._UCSRnA._RXC = false; + USART._UCSRnB._TXB8 = false; + USART._UCSRnB._RXB8 = false; + USART._UCSRnB._UCSZn2 = false; + USART._UCSRnB._TXEN = false; + USART._UCSRnB._RXEN = false; + USART._UCSRnB._UDRIE = false; + USART._UCSRnB._TXCIE = false; + USART._UCSRnB._RXCIE = false; + USART._UCSRnC._UCPOL = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + USART._UCSRnC._UCSZn0 = 1; + USART._UCSRnC._UCSZn1 = 1; + USART._UCSRnC._USBS = false; + USART._UCSRnC._UPM = 0; + USART._UCSRnC._UPM = 0; + USART._UCSRnC._UMSEL = 0; + #elif defined(__AVR_TRM05__) + USART._UCSRnC._UCPOL = 0; + USART._UCSRnC._UCPHA = 0; + USART._UCSRnC._UDORD = 0; + USART._UCSRnC.reserved1 = 0; + USART._UCSRnC._UMSEL = 0; + #endif + USART._UBRRn._UBRR = 0; + USART._UBRRn.reserved1 = 0; + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) + dwrite(USART0, USART); + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + dwrite(USART1, USART); + #endif + #ifdef __AVR_TRM01__ + dwrite(USART2, USART); + dwrite(USART3, USART); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + dwrite(_TWBR, (uint8_t)0); + + TWCR_reg_t __TWCR; + __TWCR._TWIE = false; + __TWCR.reserved1 = 0; + __TWCR._TWEN = false; + __TWCR._TWWC = false; + __TWCR._TWSTO = false; + __TWCR._TWSTA = false; + __TWCR._TWEA = false; + __TWCR._TWINT = false; + dwrite(_TWCR, __TWCR); + + TWSR_reg_t __TWSR; + __TWSR._TWPS0 = false; + __TWSR._TWPS1 = false; + __TWSR.reserved1 = 0; + __TWSR._TWS3 = 1; + __TWSR._TWS4 = 1; + __TWSR._TWS5 = 1; + __TWSR._TWS6 = 1; + __TWSR._TWS7 = 1; + dwrite(_TWSR, __TWSR); + + dwrite(_TWDR, (uint8_t)0xFF); + + TWAR_reg_t __TWAR; + __TWAR._TWGCE = false; + __TWAR._TWA = 0x7F; + dwrite(_TWAR, __TWAR); + + TWAMR_reg_t __TWAMR; + __TWAMR.reserved1 = false; + __TWAMR._TWAM = 0; + dwrite(_TWAMR, __TWAMR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + ADCSRB_reg_t __ADCSRB; + __ADCSRB._ADTS = 0; + #ifdef __AVR_TRM01__ + __ADCSRB._MUX5 = 0; + #endif + __ADCSRB.reserved1 = 0; + __ADCSRB._ACME = false; + __ADCSRB.reserved2 = 0; + dwrite(_ADCSRB, __ADCSRB); + + ACSR_reg_t __ACSR; + __ACSR._ACIS = 0; + __ACSR._ACIC = false; + __ACSR._ACIE = false; + __ACSR._ACI = false; + __ACSR._ACO = false; + __ACSR._ACBG = false; + __ACSR._ACD = false; + dwrite(_ACSR, __ACSR); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + DIDR1_reg_t __DIDR1; + __DIDR1._AIN0D = false; + __DIDR1._AIN1D = false; + __DIDR1.reserved1 = false; + dwrite(_DIDR1, __DIDR1); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + ADMUX_reg_t __ADMUX; + __ADMUX._MUX0 = 0; + __ADMUX._MUX1 = 0; + __ADMUX._MUX2 = 0; + __ADMUX._MUX3 = 0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + __ADMUX._MUX4 = 0; + #elif defined(__AVR_TRM03__) + __ADMUX.reserved1 = 0; + #endif + __ADMUX._ADLAR = 0; + __ADMUX._REFS0 = 0; + __ADMUX._REFS1 = 0; + dwrite(_ADMUX, __ADMUX); + + ADCSRA_reg_t __ADCSRA; + __ADCSRA._ADPS = 0; + __ADCSRA._ADIE = false; + __ADCSRA._ADIF = false; + __ADCSRA._ADATE = false; + __ADCSRA._ADSC = false; + __ADCSRA._ADEN = false; + dwrite(_ADCSRA, __ADCSRA); + + dwrite(_ADC, (uint16_t)0); + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + SPMCSR_reg_t __SPMCSR; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + __SPMCSR._SPMEN = false; + __SPMCSR._PGERS = false; + __SPMCSR._PGWRT = false; + __SPMCSR._BLBSET = false; + __SPMCSR._RWWSRE = false; + __SPMCSR._SIGRD = false; + __SPMCSR._RWWSB = false; + __SPMCSR._SPMIE = false; + #elif defined(__AVR_TRM03__) + #if defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328P__) + __SPMCSR._SPMEN = false; + __SPMCSR._PGERS = false; + __SPMCSR._PGWRT = false; + __SPMCSR._BLBSET = false; + __SPMCSR._RWWSRE = false; + __SPMCSR._SIGRD = false; + __SPMCSR._RWWSB = false; + __SPMCSR._SPMIE = false; + #else + __SPMCSR._SPMEN = false; + __SPMCSR._PGERS = false; + __SPMCSR._PGWRT = false; + __SPMCSR._BLBSET = false; + __SPMCSR.reserved1 = false; + __SPMCSR._SIGRD = false; + __SPMCSR.reserved2 = false; + __SPMCSR._SPMIE = false; + #endif + #endif + dwrite(_SPMCSR, __SPMCSR); + #endif + + // TODO: add the __AVR_TRM04__ initializations, if required (mostly USB related) +} + +struct pin_dev_state_t { + #ifdef __AVR_TRM01__ + uint8_t _SRE : 1; // port A + uint8_t _COM0B : 2; + uint8_t _COM1A : 2; + uint8_t _COM1B : 2; + uint8_t _COM1C : 2; + uint8_t _COM2A : 2; + uint8_t _COM2B : 2; + uint8_t _COM3A : 2; + uint8_t _COM3B : 2; + uint8_t _COM3C : 2; + uint8_t _COM4A : 2; + uint8_t _COM4B : 2; + uint8_t _COM4C : 2; + uint8_t _COM5A : 2; + uint8_t _COM5B : 2; + uint8_t _COM5C : 2; + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; // INTn + uint8_t _PCIE2 : 1; + uint8_t _SPE : 1; + uint8_t _USART0_RXEN : 1; + uint8_t _USART0_TXEN : 1; + uint8_t _USART1_RXEN : 1; + uint8_t _USART1_TXEN : 1; + uint8_t _USART2_RXEN : 1; + uint8_t _USART2_TXEN : 1; + uint8_t _USART3_RXEN : 1; + uint8_t _USART3_TXEN : 1; + //uint8_t _JTAGEN : 1; + uint8_t _AS2 : 1; + #elif defined(__AVR_TRM02__) + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; + uint8_t _PCIE2 : 1; + uint8_t _PCIE3 : 1; + uint8_t _ADC7D : 1; + uint8_t _ADC6D : 1; + uint8_t _ADC5D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC0D : 1; + uint8_t _SPE : 1; + uint8_t _COM0A : 2; + uint8_t _COM0B : 2; + uint8_t _COM2A : 2; + uint8_t _COM2B : 2; + uint8_t _COM1A : 2; + uint8_t _COM1B : 2; + //uint8_t _JTAGEN : 1; + uint8_t _AS2 : 1; + uint8_t _TWEN : 1; + uint8_t _USART1_TXEN : 1; + uint8_t _USART1_RXEN : 1; + uint8_t _USART0_TXEN : 1; + uint8_t _USART0_RXEN : 1; + #elif defined(__AVR_TRM03__) + uint8_t _AS2 : 1; + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; + uint8_t _PCIE2 : 1; + uint8_t _SPE : 1; + uint8_t _COM2B : 2; + uint8_t _COM2A : 2; + uint8_t _COM1B : 2; + uint8_t _COM1A : 2; + uint8_t _COM0A : 2; + uint8_t _COM0B : 2; + uint8_t _TWEN : 1; + uint8_t _ADC7D : 1; + uint8_t _ADC6D : 1; + uint8_t _ADC5D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC0D : 1; + uint8_t _UMSEL : 2; + uint8_t _USART0_TXEN : 1; + uint8_t _USART0_RXEN : 1; + #elif defined(__AVR_TRM04__) + uint8_t _SRE : 1; + uint8_t _SPE : 1; + uint8_t _COM0B : 2; + uint8_t _COM1C : 2; + uint8_t _COM1B : 2; + uint8_t _COM1A : 2; + uint8_t _COM2A : 2; + uint8_t _COM2B : 2; + uint8_t _PCIE0 : 1; + uint8_t _USART1_RXEN : 1; + uint8_t _USART1_TXEN : 1; + uint8_t _TWEN : 1; + uint8_t _INT7 : 1; + uint8_t _INT6 : 1; + uint8_t _INT5 : 1; + uint8_t _INT4 : 1; + uint8_t _INT3 : 1; + uint8_t _INT2 : 1; + uint8_t _INT1 : 1; + uint8_t _INT0; + uint8_t _UVCONE : 1; + uint8_t _UIDE : 1; + //uint8_t _JTAGEN : 1; + #elif defined(__AVR_TRM05__) + uint8_t _ADC7D : 1; + uint8_t _ADC6D : 1; + uint8_t _ADC5D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC0D : 1; + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; + uint8_t _PCIE2 : 1; + uint8_t _PCIE3 : 1; + uint8_t _SPE : 1; + uint8_t _COM0A : 2; + uint8_t _COM0B : 2; + uint8_t _COM2A : 2; + uint8_t _COM2B : 2; + uint8_t _COM1A : 2; + uint8_t _COM1B : 2; + uint8_t _AS2 : 1; + uint8_t _TWEN : 1; + uint8_t _TXEN1 : 1; + uint8_t _RXEN1 : 1; + uint8_t _TXEN0 : 1; + uint8_t _RXEN0 : 1; + uint8_t _INT2 : 1; + uint8_t _INT1 : 1; + uint8_t _INT0 : 1; + //uint8_t _JTAGEN : 1; + #endif +}; + +// AVR ArduinoCore is written like a hack-job (random peripherals enabled all-the-time). + +enum class eATmegaPort { + #ifdef __AVR_TRM01__ + PORT_A, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F, PORT_G, PORT_H, PORT_J, PORT_K, PORT_L + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + PORT_A, PORT_B, PORT_C, PORT_D + #elif defined(__AVR_TRM03__) + PORT_B, PORT_C, PORT_D + #elif defined(__AVR_TRM04__) + PORT_A, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F + #endif +}; + +struct ATmegaPinInfo { + eATmegaPort port; + uint8_t pinidx; +}; + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + #define _SPA_DIO_DDRA (eATmegaPort::PORT_A) +#endif +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + #define _SPA_DIO_DDRB (eATmegaPort::PORT_B) + #define _SPA_DIO_DDRC (eATmegaPort::PORT_C) + #define _SPA_DIO_DDRD (eATmegaPort::PORT_D) +#endif +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + #define _SPA_DIO_DDRE (eATmegaPort::PORT_E) + #define _SPA_DIO_DDRF (eATmegaPort::PORT_F) +#endif +#ifdef __AVR_TRM01__ + #define _SPA_DIO_DDRG (eATmegaPort::PORT_G) + #define _SPA_DIO_DDRH (eATmegaPort::PORT_H) + #define _SPA_DIO_DDRJ (eATmegaPort::PORT_J) + #define _SPA_DIO_DDRK (eATmegaPort::PORT_K) + #define _SPA_DIO_DDRL (eATmegaPort::PORT_L) +#endif + +#define __SPA_IFPORT_STMT(dr) if (ddrp == &D##dr) port = _SPA_DIO_D##dr; + +#ifdef _SPA_DIO_DDRA + #define _SPA_IFPORT_PORTA __SPA_IFPORT_STMT(DRA) +#else + #define _SPA_IFPORT_PORTA +#endif +#ifdef _SPA_DIO_DDRB + #define _SPA_IFPORT_PORTB __SPA_IFPORT_STMT(DRB) +#else + #define _SPA_IFPORT_PORTB +#endif +#ifdef _SPA_DIO_DDRC + #define _SPA_IFPORT_PORTC __SPA_IFPORT_STMT(DRC) +#else + #define _SPA_IFPORT_PORTC +#endif +#ifdef _SPA_DIO_DDRD + #define _SPA_IFPORT_PORTD __SPA_IFPORT_STMT(DRD) +#else + #define _SPA_IFPORT_PORTD +#endif +#ifdef _SPA_DIO_DDRE + #define _SPA_IFPORT_PORTE __SPA_IFPORT_STMT(DRE) +#else + #define _SPA_IFPORT_PORTE +#endif +#ifdef _SPA_DIO_DDRF + #define _SPA_IFPORT_PORTF __SPA_IFPORT_STMT(DRF) +#else + #define _SPA_IFPORT_PORTF +#endif +#ifdef _SPA_DIO_DDRG + #define _SPA_IFPORT_PORTG __SPA_IFPORT_STMT(DRG) +#else + #define _SPA_IFPORT_PORTG +#endif +#ifdef _SPA_DIO_DDRH + #define _SPA_IFPORT_PORTH __SPA_IFPORT_STMT(DRH) +#else + #define _SPA_IFPORT_PORTH +#endif +#ifdef _SPA_DIO_DDRJ + #define _SPA_IFPORT_PORTJ __SPA_IFPORT_STMT(DRJ) +#else + #define _SPA_IFPORT_PORTJ +#endif +#ifdef _SPA_DIO_DDRK + #define _SPA_IFPORT_PORTK __SPA_IFPORT_STMT(DRK) +#else + #define _SPA_IFPORT_PORTK +#endif +#ifdef _SPA_DIO_DDRL + #define _SPA_IFPORT_PORTL __SPA_IFPORT_STMT(DRL) +#else + #define _SPA_IFPORT_PORTL +#endif + +#define _SPA_RESOLVE_DIO(ddr) _SPA_DIO_##ddr +#define _SPA_DIOn_PORTRET(val, n) if (val == n) { \ + auto *ddrp = &DIO##n##_DDR; \ + eATmegaPort port; \ + _SPA_IFPORT_PORTA \ + _SPA_IFPORT_PORTB \ + _SPA_IFPORT_PORTC \ + _SPA_IFPORT_PORTD \ + _SPA_IFPORT_PORTE \ + _SPA_IFPORT_PORTF \ + _SPA_IFPORT_PORTG \ + _SPA_IFPORT_PORTH \ + _SPA_IFPORT_PORTJ \ + _SPA_IFPORT_PORTK \ + _SPA_IFPORT_PORTL \ + return { port, DIO##n##_PIN }; \ + } + +inline ATmegaPinInfo _ATmega_getPinInfo(uint8_t pin) { + #if DIO_NUM > 0 + _SPA_DIOn_PORTRET(pin, 0) + #endif + #if DIO_NUM > 1 + _SPA_DIOn_PORTRET(pin, 1) + #endif + #if DIO_NUM > 2 + _SPA_DIOn_PORTRET(pin, 2) + #endif + #if DIO_NUM > 3 + _SPA_DIOn_PORTRET(pin, 3) + #endif + #if DIO_NUM > 4 + _SPA_DIOn_PORTRET(pin, 4) + #endif + #if DIO_NUM > 5 + _SPA_DIOn_PORTRET(pin, 5) + #endif + #if DIO_NUM > 6 + _SPA_DIOn_PORTRET(pin, 6) + #endif + #if DIO_NUM > 7 + _SPA_DIOn_PORTRET(pin, 7) + #endif + #if DIO_NUM > 8 + _SPA_DIOn_PORTRET(pin, 8) + #endif + #if DIO_NUM > 9 + _SPA_DIOn_PORTRET(pin, 9) + #endif + + #if DIO_NUM > 10 + _SPA_DIOn_PORTRET(pin, 10) + #endif + #if DIO_NUM > 11 + _SPA_DIOn_PORTRET(pin, 11) + #endif + #if DIO_NUM > 12 + _SPA_DIOn_PORTRET(pin, 12) + #endif + #if DIO_NUM > 13 + _SPA_DIOn_PORTRET(pin, 13) + #endif + #if DIO_NUM > 14 + _SPA_DIOn_PORTRET(pin, 14) + #endif + #if DIO_NUM > 15 + _SPA_DIOn_PORTRET(pin, 15) + #endif + #if DIO_NUM > 16 + _SPA_DIOn_PORTRET(pin, 16) + #endif + #if DIO_NUM > 17 + _SPA_DIOn_PORTRET(pin, 17) + #endif + #if DIO_NUM > 18 + _SPA_DIOn_PORTRET(pin, 18) + #endif + #if DIO_NUM > 19 + _SPA_DIOn_PORTRET(pin, 19) + #endif + + #if DIO_NUM > 20 + _SPA_DIOn_PORTRET(pin, 20) + #endif + #if DIO_NUM > 21 + _SPA_DIOn_PORTRET(pin, 21) + #endif + #if DIO_NUM > 22 + _SPA_DIOn_PORTRET(pin, 22) + #endif + #if DIO_NUM > 23 + _SPA_DIOn_PORTRET(pin, 23) + #endif + #if DIO_NUM > 24 + _SPA_DIOn_PORTRET(pin, 24) + #endif + #if DIO_NUM > 25 + _SPA_DIOn_PORTRET(pin, 25) + #endif + #if DIO_NUM > 26 + _SPA_DIOn_PORTRET(pin, 26) + #endif + #if DIO_NUM > 27 + _SPA_DIOn_PORTRET(pin, 27) + #endif + #if DIO_NUM > 28 + _SPA_DIOn_PORTRET(pin, 28) + #endif + #if DIO_NUM > 29 + _SPA_DIOn_PORTRET(pin, 29) + #endif + + #if DIO_NUM > 30 + _SPA_DIOn_PORTRET(pin, 30) + #endif + #if DIO_NUM > 31 + _SPA_DIOn_PORTRET(pin, 31) + #endif + #if DIO_NUM > 32 + _SPA_DIOn_PORTRET(pin, 32) + #endif + #if DIO_NUM > 33 + _SPA_DIOn_PORTRET(pin, 33) + #endif + #if DIO_NUM > 34 + _SPA_DIOn_PORTRET(pin, 34) + #endif + #if DIO_NUM > 35 + _SPA_DIOn_PORTRET(pin, 35) + #endif + #if DIO_NUM > 36 + _SPA_DIOn_PORTRET(pin, 36) + #endif + #if DIO_NUM > 37 + _SPA_DIOn_PORTRET(pin, 37) + #endif + #if DIO_NUM > 38 + _SPA_DIOn_PORTRET(pin, 38) + #endif + #if DIO_NUM > 39 + _SPA_DIOn_PORTRET(pin, 39) + #endif + + #if DIO_NUM > 40 + _SPA_DIOn_PORTRET(pin, 40) + #endif + #if DIO_NUM > 41 + _SPA_DIOn_PORTRET(pin, 41) + #endif + #if DIO_NUM > 42 + _SPA_DIOn_PORTRET(pin, 42) + #endif + #if DIO_NUM > 43 + _SPA_DIOn_PORTRET(pin, 43) + #endif + #if DIO_NUM > 44 + _SPA_DIOn_PORTRET(pin, 44) + #endif + #if DIO_NUM > 45 + _SPA_DIOn_PORTRET(pin, 45) + #endif + #if DIO_NUM > 46 + _SPA_DIOn_PORTRET(pin, 46) + #endif + #if DIO_NUM > 47 + _SPA_DIOn_PORTRET(pin, 47) + #endif + #if DIO_NUM > 48 + _SPA_DIOn_PORTRET(pin, 48) + #endif + #if DIO_NUM > 49 + _SPA_DIOn_PORTRET(pin, 49) + #endif + + #if DIO_NUM > 50 + _SPA_DIOn_PORTRET(pin, 50) + #endif + #if DIO_NUM > 51 + _SPA_DIOn_PORTRET(pin, 51) + #endif + #if DIO_NUM > 52 + _SPA_DIOn_PORTRET(pin, 52) + #endif + #if DIO_NUM > 53 + _SPA_DIOn_PORTRET(pin, 53) + #endif + #if DIO_NUM > 54 + _SPA_DIOn_PORTRET(pin, 54) + #endif + #if DIO_NUM > 55 + _SPA_DIOn_PORTRET(pin, 55) + #endif + #if DIO_NUM > 56 + _SPA_DIOn_PORTRET(pin, 56) + #endif + #if DIO_NUM > 57 + _SPA_DIOn_PORTRET(pin, 57) + #endif + #if DIO_NUM > 58 + _SPA_DIOn_PORTRET(pin, 58) + #endif + #if DIO_NUM > 59 + _SPA_DIOn_PORTRET(pin, 59) + #endif + + #if DIO_NUM > 60 + _SPA_DIOn_PORTRET(pin, 60) + #endif + #if DIO_NUM > 61 + _SPA_DIOn_PORTRET(pin, 61) + #endif + #if DIO_NUM > 62 + _SPA_DIOn_PORTRET(pin, 62) + #endif + #if DIO_NUM > 63 + _SPA_DIOn_PORTRET(pin, 63) + #endif + #if DIO_NUM > 64 + _SPA_DIOn_PORTRET(pin, 64) + #endif + #if DIO_NUM > 65 + _SPA_DIOn_PORTRET(pin, 65) + #endif + #if DIO_NUM > 66 + _SPA_DIOn_PORTRET(pin, 66) + #endif + #if DIO_NUM > 67 + _SPA_DIOn_PORTRET(pin, 67) + #endif + #if DIO_NUM > 68 + _SPA_DIOn_PORTRET(pin, 68) + #endif + #if DIO_NUM > 69 + _SPA_DIOn_PORTRET(pin, 69) + #endif + + #if DIO_NUM > 70 + _SPA_DIOn_PORTRET(pin, 70) + #endif + #if DIO_NUM > 71 + _SPA_DIOn_PORTRET(pin, 71) + #endif + #if DIO_NUM > 72 + _SPA_DIOn_PORTRET(pin, 72) + #endif + #if DIO_NUM > 73 + _SPA_DIOn_PORTRET(pin, 73) + #endif + #if DIO_NUM > 74 + _SPA_DIOn_PORTRET(pin, 74) + #endif + #if DIO_NUM > 75 + _SPA_DIOn_PORTRET(pin, 75) + #endif + #if DIO_NUM > 76 + _SPA_DIOn_PORTRET(pin, 76) + #endif + #if DIO_NUM > 77 + _SPA_DIOn_PORTRET(pin, 77) + #endif + #if DIO_NUM > 78 + _SPA_DIOn_PORTRET(pin, 78) + #endif + #if DIO_NUM > 79 + _SPA_DIOn_PORTRET(pin, 79) + #endif + + #if DIO_NUM > 80 + _SPA_DIOn_PORTRET(pin, 80) + #endif + #if DIO_NUM > 81 + _SPA_DIOn_PORTRET(pin, 81) + #endif + #if DIO_NUM > 82 + _SPA_DIOn_PORTRET(pin, 82) + #endif + #if DIO_NUM > 83 + _SPA_DIOn_PORTRET(pin, 83) + #endif + #if DIO_NUM > 84 + _SPA_DIOn_PORTRET(pin, 84) + #endif + #if DIO_NUM > 85 + _SPA_DIOn_PORTRET(pin, 85) + #endif + #if DIO_NUM > 86 + _SPA_DIOn_PORTRET(pin, 86) + #endif + #if DIO_NUM > 87 + _SPA_DIOn_PORTRET(pin, 87) + #endif + #if DIO_NUM > 88 + _SPA_DIOn_PORTRET(pin, 88) + #endif + #if DIO_NUM > 89 + _SPA_DIOn_PORTRET(pin, 89) + #endif + + // Default. + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) + return { eATmegaPort::PORT_A, 0 }; + #elif defined(__AVR_TRM03__) + return { eATmegaPort::PORT_B, 0 }; + #endif +} + +enum class eATmegaPeripheral { + UNDEFINED, + #ifdef __AVR_TRM01__ + PADC, PUSART0, PSPI, PTIM1, PTIM0, PTIM2, PTWI, PUSART1, PUSART2, PUSART3, PTIM3, PTIM4, PTIM5 + #elif defined(__AVR_TRM02__) + PADC, PUSART0, PSPI, PTIM1, PUSART1, PTIM0, PTIM2, PTWI, PTIM3 + #elif defined(__AVR_TRM03__) + PADC, PUSART0, PSPI, PTIM1, PTIM0, PTIM2, PTWI + #elif defined(__AVR_TRM04__) + PADC, PSPI, PTIM1, PTIM0, PTIM2, PTWI, PUSART1, PTIM3, PUSB + #elif defined(__AVR_TRM05__) + PADC, PUSART0, PSPI, PTIM1, PUSART1, PTIM0, PTIM2, PTWI + #endif + , NUM_PERIPHERALS +}; + +enum class eATmegaPinFunc : uint8_t { + #ifdef __AVR_TRM01__ + EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, + EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, + EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, + TOC0A, TOC0B, TOC1A, TOC1B, TOC1C, TOC2A, TOC2B, TOC3C, TOC3B, TOC3A, TOC4C, TOC4B, TOC4A, TOC5C, TOC5B, TOC5A, + EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, + PCI0, PCI1, PCI2, PCI3, PCI4, PCI5, PCI6, PCI7, + PCI8, PCI9, PCI10, PCI11, PCI12, PCI13, PCI14, PCI15, + PCI16, PCI17, PCI18, PCI19, PCI20, PCI21, PCI22, PCI23, + SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, + TOSC1, TOSC2, + TIMER0_CLKI, TIMER1_CLKI, TIMER3_CLKI, TIMER4_CLKI, TIMER5_CLKI, + TIMER1_ICP, TIMER3_ICP, TIMER5_ICP, TIMER4_ICP, + USART0_CLK, USART1_CLK, USART2_CLK, USART3_CLK, + USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, USART2_TXD, USART2_RXD, USART3_TXD, USART3_RXD, + TWI_SDA, TWI_CLK, + CLKO, PDO, PDI, + AIN0, AIN1, + ADC15, ADC14, ADC13, ADC12, ADC11, ADC10, ADC9, ADC8, + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 + #elif defined(__AVR_TRM02__) + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + PCI31, PCI30, PCI29, PCI28, PCI27, PCI26, PCI25, PCI24, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI15, PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + EINT2, EINT1, EINT0, + TIMER3_ICP, + TIMER3_ECI, TIMER1_ECI, TIMER0_ECI, + TIMER1_ICP, + TOC3B, TOC3A, TOC2A, TOC2B, TOC1A, TOC1B, TOC0B, TOC0A, + AIN1, AIN0, + USART0_CLK, USART1_CLK, + USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, + CLKO, + TOSC2, TOSC1, + TWI_SDA, TWI_CLK + #elif defined(__AVR_TRM03__) + ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + XTAL2, XTAL1, + TOSC2, TOSC1, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + TOC2B, TOC2A, TOC1B, TOC1A, TOC0A, TOC0B, + TIMER1_ICP, + TIMER1_ECI, TIMER0_ECI, + TWI_CLK, TWI_SDA, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + CLKO, + AIN1, AIN0, + USART_CLK, + USART_TXD, USART_RXD, + EINT1, EINT0 + #elif defined(__AVR_TRM04__) + EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, + EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, + EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, + TOC0B, TOC0A, TOC1C, TOC1B, TOC1A, TOC2B, TOC2A, TOC3A, TOC3B, TOC3C, + CLKO, PDO, PDI, + SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, + TIMER3_ICP, TIMER1_ICP, + TIMER3_CLKI, TIMER0_CLKI, TIMER1_CLKI, + USART1_CLK, USART1_TXD, USART1_RXD, + EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + TWI_SDA, TWI_CLK, + AIN1, AIN0, + TOSC2, + UID, UVCON, + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 + #elif defined(__AVR_TRM05__) + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + PCI31, PCI30, PCI29, PCI28, PCI27, PCI26, PCI25, PCI24, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI15, PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + AIN1, AIN0, + TIMER1_ICP, TIMER0_ICP, + TIMER1_ECI, TIMER0_ECI, + TOC0B, TOC0A, TOC2A, TOC2B, TOC1A, TOC1B, + TOSC2, TOSC1, + //JTAG_TDI, JTAG_TDO, JTAG_TMS, JTAG_TCK, + TWI_CLK, TWI_SDA, + EINT2, EINT1, EINT0, + CLKO, + USART0_CLK, USART0_TXD, USART0_RXD, + USART1_CLK, USART1_TXD, USART1_RXD + #endif + , NUM_FUNCS +}; + +#ifndef countof + #define countof(x) (sizeof(x) / sizeof(*x)) +#endif + +struct ATmegaPinFunctions { + inline ATmegaPinFunctions(const eATmegaPinFunc *funcs, uint8_t cnt) noexcept : funcs(funcs), cnt(cnt) {} + inline ATmegaPinFunctions() = default; + inline ATmegaPinFunctions(const ATmegaPinFunctions&) = default; + + const eATmegaPinFunc *funcs = nullptr; + uint8_t cnt = 0; + + inline bool hasFunc(eATmegaPinFunc query) const { + for (uint8_t n = 0; n < this->cnt; n++) { + eATmegaPinFunc func = this->funcs[n]; + if (func == query) return true; + } + return false; + } + template + inline bool hasFunc(eATmegaPinFunc func, otherItemType&&... items) const { + return hasFunc(func) || hasFunc(((otherItemType&&)items)...); + } + + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 0; n < this->cnt; n++) { + eATmegaPinFunc func = this->funcs[n]; + cb(func); + } + } +}; + +ATmegaPinFunctions _ATmega_getPinFunctions(int pin); + +struct ATmegaPinFuncSet { + inline ATmegaPinFuncSet() noexcept { + for (bool& f : this->funcs) f = false; + } + template + inline ATmegaPinFuncSet(eATmegaPinFunc func, funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + add(func, ((funcItemType&&)items)...); + } + template + inline ATmegaPinFuncSet(int pin, funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + addFromPin(pin, ((funcItemType&&)items)...); + } + inline ATmegaPinFuncSet(const ATmegaPinFuncSet&) = default; + + inline void add(eATmegaPinFunc value) noexcept { + this->funcs[(uint8_t)value] = true; + } + template + inline void add(eATmegaPinFunc value, funcItemType&&... items) { + add(value); + add(((eATmegaPinFunc&&)items)...); + } + + inline void addFromPin(int pin) noexcept { + ATmegaPinFunctions funcs = _ATmega_getPinFunctions(pin); + funcs.iterate( + [this]( eATmegaPinFunc func ) noexcept { this->add(func); } + ); + } + template + inline void addFromPin(int pin, itemType&&... items) noexcept { + addFromPin(pin); + addFromPin(((itemType&&)items)...); + } + + inline bool hasFunc(eATmegaPinFunc value) const noexcept { + return this->funcs[(uint8_t)value]; + } + + inline bool hasAnyFunc() const noexcept { return false; } + template + inline bool hasAnyFunc(funcItem&& item, otherFuncItem&&... funcs) const noexcept { + return hasFunc(item) || hasAnyFunc(((otherFuncItem&&)funcs)...); + } + + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 1; n < countof(this->funcs); n++) { + const bool& f = this->funcs[n]; + if (f) cb((eATmegaPinFunc)n); + } + } + +private: + bool funcs[(uint8_t)eATmegaPinFunc::NUM_FUNCS]; +}; + +inline void _ATmega_setPeripheralPower(eATmegaPeripheral peri, bool fullPower) { + bool reducePower = (fullPower == false); + switch(peri) { + #ifdef __AVR_TRM01__ + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR1._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PUSART2: _PRR1._PRUSART2 = reducePower; break; + case eATmegaPeripheral::PUSART3: _PRR1._PRUSART3 = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; + case eATmegaPeripheral::PTIM4: _PRR1._PRTIM4 = reducePower; break; + case eATmegaPeripheral::PTIM5: _PRR1._PRTIM5 = reducePower; break; + #elif defined(__AVR_TRM02__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR0._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; + #elif defined(__AVR_TRM03__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + #elif defined(__AVR_TRM04__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR1._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; + case eATmegaPeripheral::PUSB: _PRR1._PRUSB = reducePower; break; + #elif defined(__AVR_TRM05__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR0._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + #endif + case eATmegaPeripheral::UNDEFINED: case eATmegaPeripheral::NUM_PERIPHERALS: break; + } +} + +inline bool _ATmega_getPeripheralPower(eATmegaPeripheral peri) { + switch(peri) { + #ifdef __AVR_TRM01__ + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PUSART1: return _PRR1._PRUSART1 == false; + case eATmegaPeripheral::PUSART2: return _PRR1._PRUSART2 == false; + case eATmegaPeripheral::PUSART3: return _PRR1._PRUSART3 == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; + case eATmegaPeripheral::PTIM4: return _PRR1._PRTIM4 == false; + case eATmegaPeripheral::PTIM5: return _PRR1._PRTIM5 == false; + #elif defined(__AVR_TRM02__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PUSART1: return _PRR0._PRUSART1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; + #elif defined(__AVR_TRM03__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + #elif defined(__AVR_TRM04__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PUSART1: return _PRR1._PRUSART1 == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; + case eATmegaPeripheral::PUSB: return _PRR1._PRUSB == false; + #elif defined(__AVR_TRM05__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PUSART1: return _PRR0._PRUSART1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + #endif + case eATmegaPeripheral::UNDEFINED: case eATmegaPeripheral::NUM_PERIPHERALS: break; + } + return false; +} + +inline eATmegaPeripheral _ATmega_getPeripheralForFunc( eATmegaPinFunc func ) { + // In C++20 there is the "using-enum" statement. I wish we had C++20 over here... + //using enum eATmegaPinFunc; + switch(func) { + #ifdef __AVR_TRM01__ + case eATmegaPinFunc::TOC0A: case eATmegaPinFunc::TOC0B: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1C: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC3A: case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3C: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TOC4A: case eATmegaPinFunc::TOC4B: case eATmegaPinFunc::TOC4C: return eATmegaPeripheral::PTIM4; + case eATmegaPinFunc::TOC5A: case eATmegaPinFunc::TOC5B: case eATmegaPinFunc::TOC5C: return eATmegaPeripheral::PTIM5; + case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER0_CLKI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TIMER1_CLKI: case eATmegaPinFunc::TIMER1_ICP: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER3_CLKI: case eATmegaPinFunc::TIMER3_ICP: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER4_CLKI: case eATmegaPinFunc::TIMER4_ICP: return eATmegaPeripheral::PTIM4; + case eATmegaPinFunc::TIMER5_CLKI: case eATmegaPinFunc::TIMER5_ICP: return eATmegaPeripheral::PTIM5; + case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::USART2_CLK: case eATmegaPinFunc::USART2_TXD: case eATmegaPinFunc::USART2_RXD: return eATmegaPeripheral::PUSART2; + case eATmegaPinFunc::USART3_CLK: case eATmegaPinFunc::USART3_TXD: case eATmegaPinFunc::USART3_RXD: return eATmegaPeripheral::PUSART3; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::ADC15: case eATmegaPinFunc::ADC14: case eATmegaPinFunc::ADC13: case eATmegaPinFunc::ADC12: case eATmegaPinFunc::ADC11: case eATmegaPinFunc::ADC10: case eATmegaPinFunc::ADC9: case eATmegaPinFunc::ADC8: + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + #elif defined(__AVR_TRM02__) + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER3_ICP: case eATmegaPinFunc::TIMER3_ECI: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER1_ECI: case eATmegaPinFunc::TIMER1_ICP: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3A: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; + #elif defined(__AVR_TRM03__) + case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TOC2B: case eATmegaPinFunc::TOC2A: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1A: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC0A: case eATmegaPinFunc::TOC0B: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_ECI: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TWI_CLK: case eATmegaPinFunc::TWI_SDA: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::USART_CLK: case eATmegaPinFunc::USART_TXD: case eATmegaPinFunc::USART_RXD: return eATmegaPeripheral::PUSART0; + #elif defined(__AVR_TRM04__) + case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC1C: case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1A: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC2B: case eATmegaPinFunc::TOC2A: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC3A: case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3C: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER3_ICP: case eATmegaPinFunc::TIMER3_CLKI: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_CLKI: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_CLKI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::UID: case eATmegaPinFunc::UVCON: return eATmegaPeripheral::PUSB; + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + #elif defined(__AVR_TRM05__) + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_ECI: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_ICP: case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TWI_CLK: case eATmegaPinFunc::TWI_SDA: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + #endif + // There are quite some pin functions that have no peripheral assignment, and that is OK! + default: break; + } + return eATmegaPeripheral::UNDEFINED; +} + +struct ATmegaPeripheralSet { + inline ATmegaPeripheralSet() noexcept { + for (bool& f : this->funcs) f = false; + } + template + inline ATmegaPeripheralSet(funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + add(((eATmegaPinFunc&&)items)...); + } + inline ATmegaPeripheralSet(const ATmegaPeripheralSet&) = default; + + inline void add(eATmegaPeripheral value) noexcept { + this->funcs[(uint8_t)value] = true; + } + template + inline void add(eATmegaPeripheral value, funcItemType&&... items) noexcept { + add(value); + add(((funcItemType&&)items)...); + } + + inline bool hasItem(eATmegaPeripheral value) const noexcept { + return this->funcs[(uint8_t)value]; + } + template + inline bool hasItem(eATmegaPeripheral&& item, otherFuncItem&&... funcs) const noexcept { + return hasItem(item) || hasItem(((otherFuncItem&&)funcs)...); + } + + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 1; n < countof(funcs); n++) { + const bool& f = this->funcs[n]; + if (f) cb( (eATmegaPeripheral)n ); + } + } + + inline void fromPinFuncs(const ATmegaPinFuncSet& funcSet) { + funcSet.iterate( + [this]( eATmegaPinFunc func ) noexcept { + this->add( _ATmega_getPeripheralForFunc(func) ); + } + ); + } + +private: + bool funcs[(uint8_t)eATmegaPeripheral::NUM_PERIPHERALS]; +}; + +struct ATmegaPeripheralPowerGate { + inline ATmegaPeripheralPowerGate(ATmegaPeripheralSet& periSet) noexcept : periSet(periSet) { + periSet.iterate( + [this]( eATmegaPeripheral peri ) noexcept { + this->states[(uint8_t)peri] = _ATmega_getPeripheralPower(peri); + _ATmega_setPeripheralPower(peri, true); + } + ); + } + inline ATmegaPeripheralPowerGate(const ATmegaPeripheralPowerGate&) = delete; + + inline ~ATmegaPeripheralPowerGate() { + periSet.iterate( + [this]( eATmegaPeripheral peri ) noexcept { + _ATmega_setPeripheralPower(peri, this->states[(uint8_t)peri]); + } + ); + } + + inline ATmegaPeripheralPowerGate& operator = (const ATmegaPeripheralPowerGate&) = delete; + +private: + ATmegaPeripheralSet& periSet; + bool states[(uint8_t)eATmegaPeripheral::NUM_PERIPHERALS]; +}; + +inline pin_dev_state_t _ATmega_savePinAlternates(const ATmegaPinFuncSet& funcSet) { + // TODO: the manual states that registers of power-reduced peripherals cannot be read or written, and that + // the resources (GPIO pins) remain occupied during power-reduction. This is a serious problem and we should + // add power-reduction awareness to this logic! + + pin_dev_state_t state; + + ATmegaPeripheralSet periSet; + periSet.fromPinFuncs(funcSet); + + ATmegaPeripheralPowerGate pgate(periSet); + + #ifdef __AVR_TRM01__ + // See page 75ff of ATmega2560 technical reference manual. + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + state._SRE = _XMCRA._SRE; + _XMCRA._SRE = false; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI0, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI7 + )) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + state._COM1C = TIMER1._TCCRnA._COMnC; + TIMER1._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::USART1_CLK)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::USART1_CLK)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3C)) { + state._COM3C = TIMER3._TCCRnA._COMnC; + TIMER3._TCCRnA._COMnC = 0; + } + // There is an error in the technical reference manual signal mapping table + // of ATmega2560 where is says that pin 3 is mapped to OC3B, but the list + // says OC3A. + if (funcSet.hasFunc(eATmegaPinFunc::TOC3B)) { + state._COM3B = TIMER3._TCCRnA._COMnB; + TIMER3._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3A)) { + state._COM3A = TIMER3._TCCRnA._COMnA; + TIMER3._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::USART0_CLK)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + USART0._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::USART0_CLK)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + USART0._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + state._PCIE1 = _PCICR._PCIE1; + _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; + _ASSR._AS2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4C)) { + state._COM4C = TIMER4._TCCRnA._COMnC; + TIMER4._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4B)) { + state._COM4B = TIMER4._TCCRnA._COMnB; + TIMER4._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4A)) { + state._COM4A = TIMER4._TCCRnA._COMnA; + TIMER4._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_RXD, eATmegaPinFunc::USART2_CLK)) { + state._USART2_RXEN = USART2._UCSRnB._RXEN; + USART2._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_TXD, eATmegaPinFunc::USART2_CLK)) { + state._USART2_TXEN = USART2._UCSRnB._TXEN; + USART2._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + state._USART3_RXEN = USART3._UCSRnB._RXEN; + USART3._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + state._USART3_TXEN = USART3._UCSRnB._TXEN; + USART3._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16 + )) { + state._PCIE2 = _PCICR._PCIE2; + _PCICR._PCIE2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5C)) { + state._COM5C = TIMER5._TCCRnA._COMnC; + TIMER5._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5B)) { + state._COM5B = TIMER5._TCCRnA._COMnB; + TIMER5._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5A)) { + state._COM5A = TIMER5._TCCRnA._COMnA; + TIMER5._TCCRnA._COMnA = 0; + } + #elif defined(__AVR_TRM02__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC7)) { + state._ADC7D = _DIDR0._ADC7D; + _DIDR0._ADC7D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC6)) { + state._ADC6D = _DIDR0._ADC6D; + _DIDR0._ADC6D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + state._ADC5D = _DIDR0._ADC5D; + _DIDR0._ADC5D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + state._ADC4D = _DIDR0._ADC4D; + _DIDR0._ADC4D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + state._ADC3D = _DIDR0._ADC3D; + _DIDR0._ADC3D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + state._ADC2D = _DIDR0._ADC2D; + _DIDR0._ADC2D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + state._ADC1D = _DIDR0._ADC1D; + _DIDR0._ADC1D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + state._ADC0D = _DIDR0._ADC0D; + _DIDR0._ADC0D = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + state._PCIE1 = _PCICR._PCIE1; + _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; + _SPCR._SPE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + state._COM0A = TIMER0._TCCRnA._COMnA; + TIMER0._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; + _ASSR._AS2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + state._PCIE2 = _PCICR._PCIE2; + _PCICR._PCIE2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { + state._PCIE3 = _PCICR._PCIE3; + _PCICR._PCIE3 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_TXD)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_RXD)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART0_TXD)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + USART0._UCSRnB._TXEN = false; + } + // There is a bug in the ATmega164A technical reference manual where + // it says that pin 0 is mapped to USART1 RXD in the signal mapping table + // but the associated list says USART0 RXD. + if (funcSet.hasFunc(eATmegaPinFunc::USART0_RXD)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + USART0._UCSRnB._RXEN = false; + } + #elif defined(__AVR_TRM03__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; + _ASSR._AS2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; + _SPCR._SPE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + state._PCIE1 = _PCICR._PCIE1; + _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { + state._TWEN = _TWCR._TWEN; + _TWCR._TWEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + state._ADC5D = _DIDR0._ADC5D; + _DIDR0._ADC5D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + state._ADC4D = _DIDR0._ADC4D; + _DIDR0._ADC4D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + state._ADC3D = _DIDR0._ADC3D; + _DIDR0._ADC3D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + state._ADC2D = _DIDR0._ADC2D; + _DIDR0._ADC2D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + state._ADC1D = _DIDR0._ADC1D; + _DIDR0._ADC1D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + state._ADC0D = _DIDR0._ADC0D; + _DIDR0._ADC0D = false; + } + // There is a bug in the ATmega48A technical reference manual where pin 2 + // is said to be mapped to PCIE1 but logically it should be PCIE2 instead. + // The real mapping can be read in the documentation of the PCICR register. + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + state._PCIE2 = _PCICR._PCIE2; + _PCICR._PCIE2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + state._COM0A = TIMER0._TCCRnA._COMnA; + TIMER0._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_CLK)) { + state._UMSEL = USART0._UCSRnC._UMSEL; + USART0._UCSRnC._UMSEL = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_TXD)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + USART0._UCSRnB._TXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_RXD)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + USART0._UCSRnB._RXEN = false; + } + #elif defined(__AVR_TRM04__) + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + state._SRE = _XMCRA._SRE; + _XMCRA._SRE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + state._COM1C = TIMER1._TCCRnA._COMnC; + TIMER1._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; + _SPCR._SPE = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TWI_CLK)) { + state._TWEN = _TWCR._TWEN; + _TWCR._TWEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT3)) { + state._INT3 = _EIMSK._INT3; + _EIMSK._INT3 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { + state._INT2 = _EIMSK._INT2; + _EIMSK._INT2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { + state._INT1 = _EIMSK._INT1; + _EIMSK._INT1 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { + state._INT0 = _EIMSK._INT0; + _EIMSK._INT0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::UVCON)) { + state._UVCONE = _UHWCON._UVCONE; + _UHWCON._UVCONE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::UID)) { + state._UIDE = _UHWCON._UIDE; + _UHWCON._UIDE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT7)) { + state._INT7 = _EIMSK._INT7; + _EIMSK._INT7 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT6)) { + state._INT6 = _EIMSK._INT6; + _EIMSK._INT6 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT5)) { + state._INT5 = _EIMSK._INT5; + _EIMSK._INT5 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT4)) { + state._INT4 = _EIMSK._INT4; + _EIMSK._INT4 = false; + } + #elif defined(__AVR_TRM05__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + state._PCIE1 = _PCICR._PCIE1; + _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + state._PCIE2 = _PCICR._PCIE2; + _PCICR._PCIE2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { + state._PCIE3 = _PCICR._PCIE3; + _PCICR._PCIE3 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; + _SPCR._SPE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + state._COM0A = TIMER0._TCCRnA._COMnA; + TIMER0._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { + state._TWEN = _TWCR._TWEN; + _TWCR._TWEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { + state._INT2 = _EIMSK._INT2; + _EIMSK._INT2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { + state._INT1 = _EIMSK._INT1; + _EIMSK._INT1 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { + state._INT0 = _EIMSK._INT0; + _EIMSK._INT0 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::USART0_TXD)) { + state._TXEN0 = USART0._UCSRnB._TXEN; + USART0._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::USART0_RXD)) { + state._RXEN0 = USART0._UCSRnB._RXEN; + USART0._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { + state._TXEN1 = USART1._UCSRnB._TXEN; + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { + state._RXEN1 = USART1._UCSRnB._RXEN; + USART1._UCSRnB._RXEN = false; + } + #endif + + return state; +} + +inline void _ATmega_restorePinAlternates(const ATmegaPinFuncSet& funcSet, const pin_dev_state_t& state) { + ATmegaPeripheralSet periSet; + periSet.fromPinFuncs(funcSet); + + ATmegaPeripheralPowerGate pgate(periSet); + + #ifdef __AVR_TRM01__ + // See page 75ff of ATmega2560 technical reference manual. + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + _XMCRA._SRE = state._SRE; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI0, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI7 + )) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + TIMER1._TCCRnA._COMnC = state._COM1C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::USART1_CLK)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::USART1_CLK)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3C)) { + TIMER3._TCCRnA._COMnC = state._COM3C; + } + // There is an error in the technical reference manual signal mapping table + // of ATmega2560 where is says that pin 3 is mapped to OC3B, but the list + // says OC3A. + if (funcSet.hasFunc(eATmegaPinFunc::TOC3B)) { + TIMER3._TCCRnA._COMnB = state._COM3B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3A)) { + TIMER3._TCCRnA._COMnA = state._COM3A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::USART0_CLK)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::USART0_CLK)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + _PCICR._PCIE1 = state._PCIE1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + _ASSR._AS2 = state._AS2; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4C)) { + TIMER4._TCCRnA._COMnC = state._COM4C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4B)) { + TIMER4._TCCRnA._COMnB = state._COM4B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4A)) { + TIMER4._TCCRnA._COMnA = state._COM4A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_RXD, eATmegaPinFunc::USART2_CLK)) { + USART2._UCSRnB._RXEN = state._USART2_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_TXD, eATmegaPinFunc::USART2_CLK)) { + USART2._UCSRnB._TXEN = state._USART2_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + USART3._UCSRnB._RXEN = state._USART3_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + USART3._UCSRnB._TXEN = state._USART3_TXEN; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16 + )) { + _PCICR._PCIE2 = state._PCIE2; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5C)) { + TIMER5._TCCRnA._COMnC = state._COM5C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5B)) { + TIMER5._TCCRnA._COMnB = state._COM5B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5A)) { + TIMER5._TCCRnA._COMnA = state._COM5A; + } + #elif defined(__AVR_TRM02__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC7)) { + _DIDR0._ADC7D = state._ADC7D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC6)) { + _DIDR0._ADC6D = state._ADC6D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + _DIDR0._ADC5D = state._ADC5D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + _DIDR0._ADC4D = state._ADC4D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + _DIDR0._ADC3D = state._ADC3D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + _DIDR0._ADC2D = state._ADC2D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + _DIDR0._ADC1D = state._ADC1D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + _DIDR0._ADC0D = state._ADC0D; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + _PCICR._PCIE1 = state._PCIE1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + _ASSR._AS2 = state._AS2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + _PCICR._PCIE2 = state._PCIE2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { + _PCICR._PCIE3 = state._PCIE3; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_TXD)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_RXD)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART0_TXD)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + // There is a bug in the ATmega164A technical reference manual where + // it says that pin 0 is mapped to USART1 RXD in the signal mapping table + // but the associated list says USART0 RXD. + if (funcSet.hasFunc(eATmegaPinFunc::USART0_RXD)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + #elif defined(__AVR_TRM03__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + _ASSR._AS2 = state._AS2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + _PCICR._PCIE1 = state._PCIE1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { + _TWCR._TWEN = state._TWEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + _DIDR0._ADC5D = state._ADC5D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + _DIDR0._ADC4D = state._ADC4D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + _DIDR0._ADC3D = state._ADC3D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + _DIDR0._ADC2D = state._ADC2D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + _DIDR0._ADC1D = state._ADC1D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + _DIDR0._ADC0D = state._ADC0D; + } + // There is a bug in the ATmega48A technical reference manual where pin 2 + // is said to be mapped to PCIE1 but logically it should be PCIE2 instead. + // The real mapping can be read in the documentation of the PCICR register. + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + _PCICR._PCIE2 = state._PCIE2; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_CLK)) { + USART0._UCSRnC._UMSEL = state._UMSEL; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_TXD)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_RXD)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + #elif defined(__AVR_TRM04__) + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + _XMCRA._SRE = state._SRE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + TIMER1._TCCRnA._COMnC = state._COM1C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TWI_CLK)) { + _TWCR._TWEN = state._TWEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT3)) { + _EIMSK._INT3 = state._INT3; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { + _EIMSK._INT2 = state._INT2; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { + _EIMSK._INT1 = state._INT1; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { + _EIMSK._INT0 = state._INT0; + } + if (funcSet.hasFunc(eATmegaPinFunc::UVCON)) { + _UHWCON._UVCONE = state._UVCONE; + } + if (funcSet.hasFunc(eATmegaPinFunc::UID)) { + _UHWCON._UIDE = state._UIDE; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT7)) { + _EIMSK._INT7 = state._INT7; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT6)) { + _EIMSK._INT6 = state._INT6; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT5)) { + _EIMSK._INT5 = state._INT5; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT4)) { + _EIMSK._INT4 = state._INT4; + } + #elif defined(__AVR_TRM05__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + _PCICR._PCIE1 = state._PCIE1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + _PCICR._PCIE2 = state._PCIE2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { + _PCICR._PCIE3 = state._PCIE3; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { + _TWCR._TWEN = state._TWEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { + _EIMSK._INT2 = state._INT2; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { + _EIMSK._INT1 = state._INT1; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { + _EIMSK._INT0 = state._INT0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::USART0_TXD)) { + USART0._UCSRnB._TXEN = state._TXEN0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::USART0_RXD)) { + USART0._UCSRnB._RXEN = state._RXEN0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { + USART1._UCSRnB._TXEN = state._TXEN1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { + USART1._UCSRnB._RXEN = state._RXEN1; + } + #endif +} + +inline pin_dev_state_t _ATmega_savePinAlternate(uint8_t pin) { + return _ATmega_savePinAlternates({pin}); +} + +inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& state) { + _ATmega_restorePinAlternate({pin}, state); +} + +#ifndef LOW + #define LOW 0 +#endif +#ifndef HIGH + #define HIGH 1 +#endif + +inline void _ATmega_digitalWrite(int pin, int state) { + if (pin < 0) return; + + ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); + + #ifdef __AVR_TRM01__ + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_G) { + _PORTG._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_H) { + _PORTH._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_J) { + _PORTJ._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_K) { + _PORTK._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_L) { + _PORTL._PORT.setValue(info.pinidx, state == HIGH); + } + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + #elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + #elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._PORT.setValue(info.pinidx, state == HIGH); + } + #endif +} + +inline int _ATmega_digitalRead(int pin) { + int value = LOW; + + if (pin < 0) return value; + + ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); + + #ifdef __AVR_TRM01__ + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_E) { + value = _PORTE._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_F) { + value = _PORTF._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_G) { + value = _PORTG._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_H) { + value = _PORTH._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_J) { + value = _PORTJ._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_K) { + value = _PORTK._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_L) { + value = _PORTL._PIN.getValue(info.pinidx); + } + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + #elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + #elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_E) { + value = _PORTE._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_F) { + value = _PORTF._PIN.getValue(info.pinidx); + } + #endif + + return value; +} + +#ifndef OUTPUT + #define OUTPUT 1 +#endif +#ifndef INPUT + #define INPUT 0 +#endif + +inline void _ATmega_pinMode(int pin, int mode) { + if (pin < 0) return; + + ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); + + #ifdef __AVR_TRM01__ + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_G) { + _PORTG._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_H) { + _PORTH._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_J) { + _PORTJ._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_K) { + _PORTK._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_L) { + _PORTL._DDR.setValue(info.pinidx, mode == OUTPUT); + } + #elif defined(__AVR_TRM02__) || defined(__AVR_TRM05__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + #elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + #elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._DDR.setValue(info.pinidx, mode == OUTPUT); + } + #endif +} + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) + struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t reserved1 : 5; + }; + + struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _JTAGEN : 1; + uint8_t _OCDEN : 1; + }; + + struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; + }; + + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0xFF + #endif + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0x99 + #endif + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0x62 + #endif + +#elif defined(__AVR_TRM03__) + #if defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) + struct _ATmega_efuse { + uint8_t _SELFPRGEN : 1; + uint8_t reserved1 : 7; + }; + + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xFF + #endif + + #elif defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) + struct _ATmega_efuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t reserved1 : 5; + }; + + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xF9 + #endif + + #else // defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) + struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t reserved1 : 5; + }; + + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xFF + #endif + + #endif + + #if defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) || defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) + struct _ATmega_hfuse { + uint8_t _BODLEVEL : 3; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _DWEN : 1; + uint8_t _RSTDISBL : 1; + }; + + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0xCF + #endif + + #else // defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) + struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _DWEN : 1; + uint8_t _RSTDISBL : 1; + }; + + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0xC9 + #endif + + #endif + + struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; + }; + + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0xC9 + #endif + +#elif defined(__AVR_TRM04__) + struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t _HWBE : 1; + uint8_t reserved1 : 4; + }; + + struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _JTAGEN : 1; + uint8_t _OCDEN : 1; + }; + + struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; + }; + + // Default values if not already defined. + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xF3 + #endif + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0x99 + #endif + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0x62 + #endif + +#elif defined(__AVR_TRM05__) + struct _ATmega_efuse { + uint8_t _BODLEVEL0 : 1; + uint8_t _BODLEVEL1 : 1; + uint8_t _BODLEVEL2 : 1; + uint8_t reserved1 : 5; + }; + + struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _JTAGEN : 1; + uint8_t _OCDEN : 1; + }; + + struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; + }; + + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xFF + #endif + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0x88 + #endif + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0x62 + #endif +#endif + +struct ATmega_efuse : public _ATmega_efuse { + inline ATmega_efuse(uint8_t val = 0) { *(uint8_t*)this = val; } + inline ATmega_efuse(const ATmega_efuse&) = default; +}; +struct ATmega_hfuse : public _ATmega_hfuse { + inline ATmega_hfuse(uint8_t val = 0) { *(uint8_t*)this = val; } + inline ATmega_hfuse(const ATmega_hfuse&) = default; +}; +struct ATmega_lfuse : public _ATmega_lfuse { + inline ATmega_lfuse(uint8_t val = 0) { *(uint8_t*)this = val; } + inline ATmega_lfuse(const ATmega_lfuse&) = default; +}; diff --git a/Marlin/src/HAL/AVR/spi_pins.h b/Marlin/src/HAL/AVR/spi_pins.h index 831972938a..934b6e3b14 100644 --- a/Marlin/src/HAL/AVR/spi_pins.h +++ b/Marlin/src/HAL/AVR/spi_pins.h @@ -23,43 +23,41 @@ /** * Define SPI Pins: SCK, MISO, MOSI, SS + * Platform pins have parentheses, e.g., "(53)", so we cannot use them. */ #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) - #define AVR_SCK_PIN 13 - #define AVR_MISO_PIN 12 - #define AVR_MOSI_PIN 11 - #define AVR_SS_PIN 10 + #define _PIN_SPI_SCK 13 + #define _PIN_SPI_MISO 12 + #define _PIN_SPI_MOSI 11 + #define _PIN_SPI_SS 10 #elif defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) - #define AVR_SCK_PIN 7 - #define AVR_MISO_PIN 6 - #define AVR_MOSI_PIN 5 - #define AVR_SS_PIN 4 + #define _PIN_SPI_SCK 7 + #define _PIN_SPI_MISO 6 + #define _PIN_SPI_MOSI 5 + #define _PIN_SPI_SS 4 #elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) - #define AVR_SCK_PIN 52 - #define AVR_MISO_PIN 50 - #define AVR_MOSI_PIN 51 - #define AVR_SS_PIN 53 + #define _PIN_SPI_SCK 52 + #define _PIN_SPI_MISO 50 + #define _PIN_SPI_MOSI 51 + #define _PIN_SPI_SS 53 #elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) - #define AVR_SCK_PIN 21 - #define AVR_MISO_PIN 23 - #define AVR_MOSI_PIN 22 - #define AVR_SS_PIN 20 + #define _PIN_SPI_SCK 21 + #define _PIN_SPI_MISO 23 + #define _PIN_SPI_MOSI 22 + #define _PIN_SPI_SS 20 #elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) - #define AVR_SCK_PIN 10 - #define AVR_MISO_PIN 12 - #define AVR_MOSI_PIN 11 - #define AVR_SS_PIN 16 + #define _PIN_SPI_SCK 10 + #define _PIN_SPI_MISO 12 + #define _PIN_SPI_MOSI 11 + #define _PIN_SPI_SS 16 #endif #ifndef SD_SCK_PIN - #define SD_SCK_PIN AVR_SCK_PIN + #define SD_SCK_PIN _PIN_SPI_SCK #endif #ifndef SD_MISO_PIN - #define SD_MISO_PIN AVR_MISO_PIN + #define SD_MISO_PIN _PIN_SPI_MISO #endif #ifndef SD_MOSI_PIN - #define SD_MOSI_PIN AVR_MOSI_PIN -#endif -#ifndef SD_SS_PIN - #define SD_SS_PIN AVR_SS_PIN + #define SD_MOSI_PIN _PIN_SPI_MOSI #endif diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 33c3880b6b..1800da0985 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -26,7 +28,7 @@ // ------------------------ typedef uint16_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) // ------------------------ // Defines @@ -44,15 +46,14 @@ typedef uint16_t hal_timer_t; #define MF_TIMER_TEMP 0 #endif -#define TEMP_TIMER_FREQUENCY ((F_CPU) / 64.0 / 256.0) +#define TEMP_TIMER_FREQUENCY (((F_CPU) + 0x2000) / 0x4000) -#define STEPPER_TIMER_RATE HAL_TIMER_RATE -#define STEPPER_TIMER_PRESCALE 8 -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Cannot be of type double +#define STEPPER_TIMER_RATE HAL_TIMER_RATE +#define STEPPER_TIMER_PRESCALE 8 +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A) #define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A) @@ -109,8 +110,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { * (otherwise, characters will be lost due to UART overflow). * Then: Stepper, Endstops, Temperature, and -finally- all others. */ -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/AVR/u8g/LCD_defines.h b/Marlin/src/HAL/AVR/u8g/LCD_defines.h new file mode 100644 index 0000000000..91858c0dbf --- /dev/null +++ b/Marlin/src/HAL/AVR/u8g/LCD_defines.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * AVR LCD-specific defines + */ + +uint8_t u8g_com_HAL_AVR_sw_sp_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); +#define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_AVR_sw_sp_fn diff --git a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g/u8g_com_HAL_AVR_sw_spi.cpp similarity index 91% rename from Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp rename to Marlin/src/HAL/AVR/u8g/u8g_com_HAL_AVR_sw_spi.cpp index 45b54379db..f4fa1eb428 100644 --- a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp +++ b/Marlin/src/HAL/AVR/u8g/u8g_com_HAL_AVR_sw_spi.cpp @@ -55,12 +55,12 @@ #if defined(ARDUINO) && !defined(ARDUINO_ARCH_STM32) && !defined(ARDUINO_ARCH_SAM) -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_MARLINUI_U8GLIB -#include "../shared/Marduino.h" -#include "../shared/Delay.h" +#include "../../shared/Marduino.h" +#include "../../shared/Delay.h" #include @@ -88,7 +88,7 @@ void u8g_spiSend_sw_AVR_mode_0(uint8_t val) { volatile uint8_t *outData = u8g_outData, *outClock = u8g_outClock; U8G_ATOMIC_START(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (val & 0x80) *outData |= bitData; else @@ -108,7 +108,7 @@ void u8g_spiSend_sw_AVR_mode_3(uint8_t val) { volatile uint8_t *outData = u8g_outData, *outClock = u8g_outClock; U8G_ATOMIC_START(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { *outClock &= bitNotClock; if (val & 0x80) *outData |= bitData; @@ -120,8 +120,7 @@ void u8g_spiSend_sw_AVR_mode_3(uint8_t val) { U8G_ATOMIC_END(); } - -#if ENABLED(FYSETC_MINI_12864) +#if U8G_SPI_USE_MODE_3 #define SPISEND_SW_AVR u8g_spiSend_sw_AVR_mode_3 #else #define SPISEND_SW_AVR u8g_spiSend_sw_AVR_mode_0 @@ -144,9 +143,9 @@ uint8_t u8g_com_HAL_AVR_sw_sp_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void break; case U8G_COM_MSG_CHIP_SELECT: - #if ENABLED(FYSETC_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active + #if U8G_SPI_USE_MODE_3 // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active u8g_com_arduino_digital_write(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_com_arduino_digital_write(u8g, U8G_PI_CS, LOW); } diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index 4353f16497..19a174259a 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -25,7 +27,6 @@ #ifdef ARDUINO_ARCH_SAM #include "../../inc/MarlinConfig.h" -#include "../../MarlinCore.h" #include #include "usb/usb_task.h" @@ -45,8 +46,8 @@ uint16_t MarlinHAL::adc_result; #endif void MarlinHAL::init() { - #if ENABLED(SDSUPPORT) - OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up + #if HAS_MEDIA + OUT_WRITE(SD_SS_PIN, HIGH); // Try to set SDSS inactive before any other SPI users start up #endif usb_task_init(); // Initialize the USB stack TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler @@ -100,6 +101,10 @@ void watchdogSetup() { #if ENABLED(USE_WATCHDOG) + #ifndef WATCHDOG_PIO_RESET + #define WATCHDOG_PIO_RESET + #endif + // 4 seconds timeout uint32_t timeout = TERN(WATCHDOG_DURATION_8S, 8000, 4000); @@ -113,15 +118,16 @@ void watchdogSetup() { 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. + uint32_t value = (0 + | WDT_MR_WDV(timeout) // With the specified timeout + | WDT_MR_WDD(timeout) // and no invalid write window + #if NONE(WATCHDOG_PIO_RESET, SAMV70, SAMV71, SAME70, SAMS70) + | WDT_MR_WDRPROC // WDT fault resets processor only with this flag. + // Omit to also reset the PIO controller. + #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. diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 4d3f4823a5..f83668ca9d 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -35,67 +35,9 @@ #include -#include "../../core/serial_hook.h" - -// ------------------------ -// Serial ports -// ------------------------ - -typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; -typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; -typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; -typedef ForwardSerial1Class< decltype(Serial3) > DefaultSerial4; -extern DefaultSerial1 MSerial0; -extern DefaultSerial2 MSerial1; -extern DefaultSerial3 MSerial2; -extern DefaultSerial4 MSerial3; - -#define _MSERIAL(X) MSerial##X -#define MSERIAL(X) _MSERIAL(X) - -#if SERIAL_PORT == -1 || ENABLED(EMERGENCY_PARSER) - #define MYSERIAL1 customizedSerial1 -#elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL1 MSERIAL(SERIAL_PORT) -#else - #error "The required SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." -#endif - -#ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == -1 || ENABLED(EMERGENCY_PARSER) - #define MYSERIAL2 customizedSerial2 - #elif WITHIN(SERIAL_PORT_2, 0, 3) - #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) - #else - #error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial." - #endif -#endif - -#ifdef SERIAL_PORT_3 - #if SERIAL_PORT_3 == -1 || ENABLED(EMERGENCY_PARSER) - #define MYSERIAL3 customizedSerial3 - #elif WITHIN(SERIAL_PORT_3, 0, 3) - #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) - #else - #error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial." - #endif -#endif - -#ifdef MMU2_SERIAL_PORT - #if WITHIN(MMU2_SERIAL_PORT, 0, 3) - #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) - #else - #error "MMU2_SERIAL_PORT must be from 0 to 3." - #endif -#endif - -#ifdef LCD_SERIAL_PORT - #if WITHIN(LCD_SERIAL_PORT, 0, 3) - #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) - #else - #error "LCD_SERIAL_PORT must be from 0 to 3." - #endif -#endif +// +// Serial Ports +// #include "MarlinSerial.h" #include "MarlinSerialUSB.h" @@ -123,11 +65,11 @@ typedef Servo hal_servo_t; // // ADC // -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 #ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) + #define analogInputToDigitalPin(p) pin_t((p < 12U) ? (p) + 54U : -1) #endif // @@ -190,7 +132,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset @@ -210,7 +152,7 @@ public: static void adc_init() {} // Called by Temperature::init for each sensor at startup - static void adc_enable(const uint8_t ch) {} + static void adc_enable(const uint8_t /*ch*/) {} // Begin ADC sampling on the given channel. Called from Temperature::isr! static void adc_start(const uint8_t ch) { adc_result = analogRead(ch); } diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index 7e3fe01356..e44549357e 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -42,7 +42,7 @@ // Public functions // ------------------------ -#if EITHER(DUE_SOFTWARE_SPI, FORCE_SOFT_SPI) +#if ANY(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI @@ -208,8 +208,8 @@ A("str %[sck_mask],[%[sck_port],#0x4]") /* CODR */ A("bfi %[bin],%[work],#0,#1") /* Store read bit as the bit 0 */ - : [bin]"+r"(bin), - [work]"+r"(work) + : [bin]"+r"( bin ), + [work]"+r"( work ) : [bitband_miso_port]"r"( BITBAND_MISO_PORT ), [sck_mask]"r"( SCK_MASK ), [sck_port]"r"( SCK_PORT_PLUS30 ) @@ -247,12 +247,12 @@ b <<= 1; // little setup time WRITE(SD_SCK_PIN, HIGH); - DELAY_NS(spiDelayNS); + DELAY_NS_VAR(spiDelayNS); b |= (READ(SD_MISO_PIN) != 0); WRITE(SD_SCK_PIN, LOW); - DELAY_NS(spiDelayNS); + DELAY_NS_VAR(spiDelayNS); } while (--bits); return b; } @@ -350,7 +350,7 @@ static void spiRxBlock0(uint8_t *ptr, uint32_t todo) { uint32_t bin = 0; uint32_t work = 0; - uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS( ((uint32_t)PORT(SD_MISO_PIN))+0x3C, PIN_SHIFT(SD_MISO_PIN)); /* PDSR of port in bitband area */ + uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS(((uint32_t)PORT(SD_MISO_PIN))+0x3C, PIN_SHIFT(SD_MISO_PIN)); /* PDSR of port in bitband area */ uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SD_SCK_PIN)) + 0x30; /* SODR of port */ uint32_t SCK_MASK = PIN_MASK(SD_SCK_PIN); @@ -412,10 +412,10 @@ A("strb.w %[bin], [%[ptr]], #1") /* Store read value into buffer, increment buffer pointer */ A("bne.n loop%=") /* Repeat until done */ - : [ptr]"+r"(ptr), - [todo]"+r"(todo), - [bin]"+r"(bin), - [work]"+r"(work) + : [ptr]"+r"( ptr ), + [todo]"+r"( todo ), + [bin]"+r"( bin ), + [work]"+r"( work ) : [bitband_miso_port]"r"( BITBAND_MISO_PORT ), [sck_mask]"r"( SCK_MASK ), [sck_port]"r"( SCK_PORT_PLUS30 ) @@ -600,9 +600,8 @@ OUT_WRITE(SPI_EEPROM1_CS_PIN, HIGH); OUT_WRITE(SPI_EEPROM2_CS_PIN, HIGH); OUT_WRITE(SPI_FLASH_CS_PIN, HIGH); - WRITE(SD_SS_PIN, HIGH); - - OUT_WRITE(SDSS, LOW); + OUT_WRITE(SD_SS_PIN, HIGH); + WRITE(SD_SS_PIN, LOW); PIO_Configure( g_APinDescription[SPI_PIN].pPort, @@ -767,7 +766,7 @@ // Disable PIO on A26 and A27 REG_PIOA_PDR = 0x0C000000; - OUT_WRITE(SDSS, HIGH); + OUT_WRITE(SD_SS_PIN, HIGH); // Reset SPI0 (from sam lib) SPI0->SPI_CR = SPI_CR_SPIDIS; diff --git a/Marlin/src/HAL/DUE/InterruptVectors.cpp b/Marlin/src/HAL/DUE/InterruptVectors.cpp index e4e0ce99f2..70795d1c30 100644 --- a/Marlin/src/HAL/DUE/InterruptVectors.cpp +++ b/Marlin/src/HAL/DUE/InterruptVectors.cpp @@ -41,7 +41,7 @@ practice, we need alignment to 256 bytes to make this work in all cases */ __attribute__ ((aligned(256))) -static DeviceVectors ram_tab = { nullptr }; +static DeviceVectors ram_tab[61] = { nullptr }; /** * This function checks if the exception/interrupt table is already in SRAM or not. diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index 638f7a1007..2e80b4c8d1 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -31,7 +31,6 @@ #include "MarlinSerial.h" #include "InterruptVectors.h" -#include "../../MarlinCore.h" template typename MarlinSerial::ring_buffer_r MarlinSerial::rx_buffer = { 0, 0, { 0 } }; template typename MarlinSerial::ring_buffer_t MarlinSerial::tx_buffer = { 0 }; @@ -474,7 +473,6 @@ void MarlinSerial::flushTX() { } } - // If not using the USB port as serial port #if defined(SERIAL_PORT) && SERIAL_PORT >= 0 template class MarlinSerial< MarlinSerialCfg >; diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h index 5a61bffee0..cee0857d2b 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -30,8 +30,24 @@ #include #include "../../inc/MarlinConfigPre.h" +#include "../../core/types.h" #include "../../core/serial_hook.h" +typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; +typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; +typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; +typedef ForwardSerial1Class< decltype(Serial3) > DefaultSerial4; +extern DefaultSerial1 MSerial0; +extern DefaultSerial2 MSerial1; +extern DefaultSerial3 MSerial2; +extern DefaultSerial4 MSerial3; + +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 3 +#define EP_SERIAL_PORT(N) customizedSerial##N +#define USB_SERIAL_PORT(N) customizedSerial##N +#include "../shared/serial_ports.h" + // Define constants and variables for buffering incoming serial data. We're // using a ring buffer (I think), in which rx_buffer_head is the index of the // location to which to write the next incoming character and rx_buffer_tail @@ -52,10 +68,6 @@ // #error "TX_BUFFER_SIZE must be 0, a power of 2 greater than 1, and no greater than 256." //#endif -// Templated type selector -template struct TypeSelector { typedef T type;} ; -template struct TypeSelector { typedef F type; }; - // Templated structure wrapper template struct StructWrapper { constexpr StructWrapper(int) {} @@ -76,7 +88,7 @@ protected: static constexpr int HWUART_IRQ_ID = IRQ_IDS[Cfg::PORT]; // Base size of type on buffer size - typedef typename TypeSelector<(Cfg::RX_SIZE>256), uint16_t, uint8_t>::type ring_buffer_pos_t; + typedef uvalue_t(Cfg::RX_SIZE - 1) ring_buffer_pos_t; struct ring_buffer_r { volatile ring_buffer_pos_t head, tail; diff --git a/Marlin/src/HAL/DUE/MinSerial.cpp b/Marlin/src/HAL/DUE/MinSerial.cpp index e5b3dbfe6f..505a712aa9 100644 --- a/Marlin/src/HAL/DUE/MinSerial.cpp +++ b/Marlin/src/HAL/DUE/MinSerial.cpp @@ -73,18 +73,18 @@ void install_min_serial() { } #if DISABLED(DYNAMIC_VECTORTABLE) -extern "C" { - __attribute__((naked)) void JumpHandler_ASM() { - __asm__ __volatile__ ( - "b CommonHandler_ASM\n" - ); + extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); } - void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); -} #endif #endif // POSTMORTEM_DEBUGGING diff --git a/Marlin/src/HAL/DUE/Servo.cpp b/Marlin/src/HAL/DUE/Servo.cpp index 2dab88238d..2f72d66b9b 100644 --- a/Marlin/src/HAL/DUE/Servo.cpp +++ b/Marlin/src/HAL/DUE/Servo.cpp @@ -50,7 +50,7 @@ static Flags<_Nbr_16timers> DisablePending; // ISR should disable the timer at the next timer reset // ------------------------ -/// Interrupt handler for the TC0 channel 1. +// Interrupt handler for the TC0 channel 1. // ------------------------ void Servo_Handler(const timer16_Sequence_t, Tc*, const uint8_t); diff --git a/Marlin/src/HAL/DUE/Tone.cpp b/Marlin/src/HAL/DUE/Tone.cpp index 4bc8142aba..743cae9d70 100644 --- a/Marlin/src/HAL/DUE/Tone.cpp +++ b/Marlin/src/HAL/DUE/Tone.cpp @@ -24,7 +24,7 @@ /** * Description: Tone function for Arduino Due and compatible (SAM3X8E) - * Derived from https://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012 + * Derived from https://forum.arduino.cc/t/arduino-due-and-tone/133302/13 */ #ifdef ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom/eeprom_flash.cpp similarity index 98% rename from Marlin/src/HAL/DUE/eeprom_flash.cpp rename to Marlin/src/HAL/DUE/eeprom/eeprom_flash.cpp index 607764155b..b33d15e106 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -22,7 +21,7 @@ */ #ifdef ARDUINO_ARCH_SAM -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(FLASH_EEPROM_EMULATION) @@ -133,7 +132,7 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes curGroup = 0xFF; // Current FLASH group #define DEBUG_OUT ENABLED(EE_EMU_DEBUG) -#include "../../core/debug_out.h" +#include "../../../core/debug_out.h" static void ee_Dump(const int page, const void *data) { @@ -292,7 +291,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { uint32_t *p1 = (uint32_t*)addrflash; uint32_t *p2 = (uint32_t*)data; int count = 0; - for (i =0; i> 2; i++) { + for (i = 0; i < PageSize >> 2; i++) { if (p1[i] != p2[i]) { uint32_t delta = p1[i] ^ p2[i]; while (delta) { @@ -954,19 +953,19 @@ static void ee_Init() { /* PersistentStore -----------------------------------------------------------*/ -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_api.h" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { ee_Init(); return true; } bool PersistentStore::access_finish() { ee_Flush(); return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { uint16_t written = 0; while (size--) { - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); uint8_t v = *value; if (v != ee_Read(uint32_t(p))) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! ee_Write(uint32_t(p), v); @@ -985,7 +984,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t c = ee_Read(uint32_t(pos)); + uint8_t c = ee_Read(uint32_t(REAL_EEPROM_ADDR(pos))); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom/eeprom_wired.cpp similarity index 84% rename from Marlin/src/HAL/DUE/eeprom_wired.cpp rename to Marlin/src/HAL/DUE/eeprom/eeprom_wired.cpp index 557a2f2cff..cf9233816c 100644 --- a/Marlin/src/HAL/DUE/eeprom_wired.cpp +++ b/Marlin/src/HAL/DUE/eeprom/eeprom_wired.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -22,7 +21,7 @@ */ #ifdef ARDUINO_ARCH_SAM -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if USE_WIRED_EEPROM @@ -31,20 +30,20 @@ * with simple implementations supplied by Marlin. */ -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" #ifndef MARLIN_EEPROM_SIZE #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { uint16_t written = 0; while (size--) { - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); uint8_t v = *value; if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); @@ -63,7 +62,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t c = eeprom_read_byte((uint8_t*)pos); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h index c1bbcb121b..798ca4f0cb 100644 --- a/Marlin/src/HAL/DUE/endstop_interrupts.h +++ b/Marlin/src/HAL/DUE/endstop_interrupts.h @@ -47,33 +47,34 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); - TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h index a609210d81..77bc1911d8 100644 --- a/Marlin/src/HAL/DUE/fastio.h +++ b/Marlin/src/HAL/DUE/fastio.h @@ -189,12 +189,12 @@ */ // UART -#define RXD DIO0 -#define TXD DIO1 +#define RXD 0 +#define TXD 1 // TWI (I2C) -#define SCL DIO21 -#define SDA DIO20 +#define SCL 21 +#define SDA 20 /** * pins diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp index 800915ff69..745e4205bc 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp +++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp @@ -40,11 +40,12 @@ * Some jitter in the Vref signal is OK so the interrupt priority is left at its default value. */ -#include "../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfigPre.h" #if MB(PRINTRBOARD_G2) #include "G2_PWM.h" +#include "../../../module/stepper.h" #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) #define G2_PWM_X 1 @@ -56,16 +57,12 @@ #else #define G2_PWM_Y 0 #endif -#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) +#if HAS_MOTOR_CURRENT_PWM_Z #define G2_PWM_Z 1 #else #define G2_PWM_Z 0 #endif -#if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - #define G2_PWM_E 1 -#else - #define G2_PWM_E 0 -#endif +#define G2_PWM_E HAS_MOTOR_CURRENT_PWM_E #define G2_MASK_X(V) (G2_PWM_X * (V)) #define G2_MASK_Y(V) (G2_PWM_Y * (V)) #define G2_MASK_Z(V) (G2_PWM_Z * (V)) @@ -80,17 +77,22 @@ PWM_map ISR_table[NUM_PWMS] = PWM_MAP_INIT; void Stepper::digipot_init() { - #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) - OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins + #if G2_PWM_X + OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, LOW); // init pins #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y) - OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0); + #if G2_PWM_Y + OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, LOW); #endif #if G2_PWM_Z - OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0); + OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, LOW); #endif #if G2_PWM_E - OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0); + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, LOW); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E0) + OUT_WRITE(MOTOR_CURRENT_PWM_E0_PIN, LOW); + #endif #endif #define WPKEY (0x50574D << 8) // “PWM†in ASCII diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.h b/Marlin/src/HAL/DUE/fastio/G2_PWM.h index dc4edffff8..7fb2aaf7a8 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_PWM.h +++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.h @@ -26,10 +26,7 @@ * PR #7500. It is hardwired for the PRINTRBOARD_G2 Motor Current needs. */ -#include "../../../inc/MarlinConfigPre.h" -#include "../../../module/stepper.h" -//C:\Users\bobku\Documents\GitHub\Marlin-Bob-2\Marlin\src\module\stepper.h -//C:\Users\bobku\Documents\GitHub\Marlin-Bob-2\Marlin\src\HAL\HAL_DUE\G2_PWM.h +#include #define PWM_PERIOD_US 100 // base repetition rate in micro seconds @@ -49,7 +46,6 @@ extern volatile uint32_t *SODR_A, *SODR_B, *CODR_A, *CODR_B; #define PWM_MAP_INIT_ROW(IO,ZZ) { ZZ == 'A' ? SODR_A : SODR_B, ZZ == 'A' ? CODR_A : CODR_B, 1 << _PIN(IO) } - #define PWM_MAP_INIT { PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_X_PIN, 'B'), \ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Y_PIN, 'B'), \ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Z_PIN, 'B'), \ @@ -63,7 +59,7 @@ extern PWM_map ISR_table[NUM_PWMS]; extern uint32_t motor_current_setting[3]; #define IR_BIT(p) (WITHIN(p, 0, 3) ? (p) : (p) + 4) -#define COPY_ACTIVE_TABLE() do{ LOOP_L_N(i, 6) work_table[i] = active_table[i]; }while(0) +#define COPY_ACTIVE_TABLE() do{ for (uint8_t i = 0; i < 6; ++i) work_table[i] = active_table[i]; }while(0) #define PWM_MR0 19999 // base repetition rate minus one count - 20mS #define PWM_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output diff --git a/Marlin/src/HAL/DUE/fastio/G2_pins.h b/Marlin/src/HAL/DUE/fastio/G2_pins.h index 80c87bd392..38fcc5e5df 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_pins.h +++ b/Marlin/src/HAL/DUE/fastio/G2_pins.h @@ -168,7 +168,6 @@ const G2_PinDescription G2_g_APinDescription[] = { { PIOB, PIO_PB21, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 52 { PIOB, PIO_PB14, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 53 - // 54 .. 65 - Analog pins // ---------------------- { PIOA, PIO_PA16X1_AD7, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC0, ADC7, NOT_ON_PWM, NOT_ON_TIMER }, // AD0 diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h b/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h index 5867414447..5f1c4b1601 100644 --- a/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h @@ -20,7 +20,3 @@ * */ #pragma once - -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/DUE." -#endif diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_post.h b/Marlin/src/HAL/DUE/inc/Conditionals_post.h index ce6d3fdde2..295596b78b 100644 --- a/Marlin/src/HAL/DUE/inc/Conditionals_post.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_post.h @@ -23,6 +23,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_type.h b/Marlin/src/HAL/DUE/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/DUE/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h index 13484f7029..599e2aa464 100644 --- a/Marlin/src/HAL/DUE/inc/SanityCheck.h +++ b/Marlin/src/HAL/DUE/inc/SanityCheck.h @@ -25,6 +25,10 @@ * Test Arduino Due specific configuration values for errors at compile-time. */ +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for HAL/DUE." +#endif + /** * Check for common serial pin conflicts */ @@ -36,15 +40,15 @@ || 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. +#if SERIAL_IN_USE(0) // D0-D1. No known conflicts. #endif -#if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19)) +#if SERIAL_IN_USE(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)) +#if SERIAL_IN_USE(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)) +#if SERIAL_IN_USE(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 @@ -64,20 +68,19 @@ * Usually the hardware SPI pins are only available to the LCD. This makes the DUE hard SPI used at the same time * as the TMC2130 soft SPI the most common setup. */ -#define _IS_HW_SPI(P) (defined(TMC_SW_##P) && (TMC_SW_##P == SD_MOSI_PIN || TMC_SW_##P == SD_MISO_PIN || TMC_SW_##P == SD_SCK_PIN)) - -#if ENABLED(SDSUPPORT) && HAS_DRIVER(TMC2130) - #if ENABLED(TMC_USE_SW_SPI) - #if DISABLED(DUE_SOFTWARE_SPI) && (_IS_HW_SPI(MOSI) || _IS_HW_SPI(MISO) || _IS_HW_SPI(SCK)) - #error "DUE hardware SPI is required but is incompatible with TMC2130 software SPI. Either disable TMC_USE_SW_SPI or use separate pins for the two SPIs." - #endif - #elif ENABLED(DUE_SOFTWARE_SPI) +#if HAS_MEDIA && HAS_DRIVER(TMC2130) + #define _IS_HW_SPI(P) (defined(TMC_SPI_##P) && (TMC_SPI_##P == SD_MOSI_PIN || TMC_SPI_##P == SD_MISO_PIN || TMC_SPI_##P == SD_SCK_PIN)) + #if DISABLED(SOFTWARE_SPI) && ENABLED(TMC_USE_SW_SPI) && (_IS_HW_SPI(MOSI) || _IS_HW_SPI(MISO) || _IS_HW_SPI(SCK)) + #error "DUE hardware SPI is required but is incompatible with TMC2130 software SPI. Either disable TMC_USE_SW_SPI or use separate pins for the two SPIs." + #endif + #if ENABLED(SOFTWARE_SPI) && DISABLED(TMC_USE_SW_SPI) #error "DUE software SPI is required but is incompatible with TMC2130 hardware SPI. Enable TMC_USE_SW_SPI to fix." #endif + #undef _IS_HW_SPI #endif #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on DUE." + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported for HAL/DUE." #endif #if HAS_TMC_SW_SERIAL diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h index df1ba415e9..e9e364dcec 100644 --- a/Marlin/src/HAL/DUE/pinsDebug.h +++ b/Marlin/src/HAL/DUE/pinsDebug.h @@ -19,13 +19,26 @@ * along with this program. If not, see . * */ +#pragma once /** - * Support routines for Due - */ - -/** - * Translation of routines & variables used by pinsDebug.h + * Pins Debugging for DUE + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) */ #include "../shared/Marduino.h" @@ -63,21 +76,20 @@ #define NUMBER_PINS_TOTAL PINS_COUNT -#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin -#define PRINT_PORT(p) -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) -#define GET_ARRAY_PIN(p) pin_array[p].pin -#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital -#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0) -#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0)) -#define IS_ANALOG(P) WITHIN(P, char(analogInputToDigitalPin(0)), char(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1))) -#define pwm_status(pin) (((g_pinStatus[pin] & 0xF) == PIN_STATUS_PWM) && \ - ((g_APinDescription[pin].ulPinAttribute & PIN_ATTR_PWM) == PIN_ATTR_PWM)) +#define digitalRead_mod(P) extDigitalRead(P) // AVR digitalRead disabled PWM before it read the pin +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define getPinByIndex(x) pin_array[x].pin +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL)) +#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0)) +#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1))) +#define pwm_status(P) (((g_pinStatus[P] & 0xF) == PIN_STATUS_PWM) && \ + ((g_APinDescription[P].ulPinAttribute & PIN_ATTR_PWM) == PIN_ATTR_PWM)) #define MULTI_NAME_PAD 14 // space needed to be pretty if not first name assigned to a pin -bool GET_PINMODE(int8_t pin) { // 1: output, 0: input +bool getValidPinMode(const pin_t pin) { // 1: output, 0: input volatile Pio* port = g_APinDescription[pin].pPort; uint32_t mask = g_APinDescription[pin].ulPin; uint8_t pin_status = g_pinStatus[pin] & 0xF; @@ -86,13 +98,15 @@ bool GET_PINMODE(int8_t pin) { // 1: output, 0: input || pwm_status(pin)); } -void pwm_details(int32_t pin) { +void printPinPWM(const int32_t pin) { if (pwm_status(pin)) { uint32_t chan = g_APinDescription[pin].ulPWMChannel; SERIAL_ECHOPGM("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY); } } +void printPinPort(const pin_t) {} + /** * DUE Board pin | PORT | Label * ----------------+--------+------- diff --git a/Marlin/src/HAL/DUE/spi_pins.h b/Marlin/src/HAL/DUE/spi_pins.h index cec22c2c37..e289c8ced2 100644 --- a/Marlin/src/HAL/DUE/spi_pins.h +++ b/Marlin/src/HAL/DUE/spi_pins.h @@ -24,41 +24,38 @@ /** * Define SPI Pins: SCK, MISO, MOSI, SS * - * Available chip select pins for HW SPI are 4 10 52 77 + * Available chip select pins for HW SPI are 4 10 52 77 87 */ -#if SDSS == 4 || SDSS == 10 || SDSS == 52 || SDSS == 77 || SDSS == 87 - #if SDSS == 4 - #define SPI_PIN 87 - #define SPI_CHAN 1 - #elif SDSS == 10 - #define SPI_PIN 77 - #define SPI_CHAN 0 - #elif SDSS == 52 - #define SPI_PIN 86 - #define SPI_CHAN 2 - #elif SDSS == 77 - #define SPI_PIN 77 - #define SPI_CHAN 0 - #else - #define SPI_PIN 87 - #define SPI_CHAN 1 - #endif - #define SD_SCK_PIN 76 - #define SD_MISO_PIN 74 - #define SD_MOSI_PIN 75 -#else - // defaults - #define DUE_SOFTWARE_SPI - #ifndef SD_SCK_PIN - #define SD_SCK_PIN 52 - #endif - #ifndef SD_MISO_PIN - #define SD_MISO_PIN 50 - #endif - #ifndef SD_MOSI_PIN - #define SD_MOSI_PIN 51 - #endif +#if SD_SS_PIN == 4 || SD_SS_PIN == 10 || SD_SS_PIN == 52 || SD_SS_PIN == 77 || SD_SS_PIN == 87 + #define SD_SCK_PIN 76 + #define SD_MISO_PIN 74 + #define SD_MOSI_PIN 75 #endif -/* A.28, A.29, B.21, C.26, C.29 */ -#define SD_SS_PIN SDSS +#if SD_SS_PIN == 4 + #define SPI_PIN 87 + #define SPI_CHAN 1 +#elif SD_SS_PIN == 10 + #define SPI_PIN 77 + #define SPI_CHAN 0 +#elif SD_SS_PIN == 52 + #define SPI_PIN 86 + #define SPI_CHAN 2 +#elif SD_SS_PIN == 77 + #define SPI_PIN 77 + #define SPI_CHAN 0 +#elif SD_SS_PIN == 87 + #define SPI_PIN 87 + #define SPI_CHAN 1 +#else + #define SOFTWARE_SPI + #ifndef SD_SCK_PIN + #define SD_SCK_PIN 52 + #endif + #ifndef SD_MISO_PIN + #define SD_MISO_PIN 50 + #endif + #ifndef SD_MOSI_PIN + #define SD_MOSI_PIN 51 + #endif +#endif diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp index e5647817b6..e388255c08 100644 --- a/Marlin/src/HAL/DUE/timers.cpp +++ b/Marlin/src/HAL/DUE/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index dc35c77e63..f892eac8f5 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -33,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define HAL_TIMER_PRESCALER 2 #define HAL_TIMER_RATE ((F_CPU) / (HAL_TIMER_PRESCALER)) // frequency of timers peripherals @@ -51,19 +52,18 @@ typedef uint32_t hal_timer_t; #define MF_TIMER_TONE 6 // index of timer to use for beeper tones #endif -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs #define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) #define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) @@ -126,4 +126,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/DUE/u8g/LCD_defines.h b/Marlin/src/HAL/DUE/u8g/LCD_defines.h new file mode 100644 index 0000000000..e85f13514f --- /dev/null +++ b/Marlin/src/HAL/DUE/u8g/LCD_defines.h @@ -0,0 +1,34 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * DUE (SAM3X8E) LCD-specific defines + */ + +uint8_t u8g_com_HAL_DUE_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); +uint8_t u8g_com_HAL_DUE_shared_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); +uint8_t u8g_com_HAL_DUE_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + +#define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_DUE_sw_spi_fn +#define U8G_COM_HAL_HW_SPI_FN u8g_com_HAL_DUE_shared_hw_spi_fn +#define U8G_COM_ST7920_HAL_SW_SPI u8g_com_HAL_DUE_ST7920_sw_spi_fn diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp b/Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_shared_hw_spi.cpp similarity index 100% rename from Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp rename to Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_shared_hw_spi.cpp diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp b/Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_st7920_sw_spi.cpp similarity index 100% rename from Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp rename to Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_st7920_sw_spi.cpp diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp b/Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_sw_spi.cpp similarity index 89% rename from Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp rename to Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_sw_spi.cpp index 68e3e74a45..a8f4dd2b03 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp +++ b/Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_sw_spi.cpp @@ -66,7 +66,7 @@ #include -#if ENABLED(FYSETC_MINI_12864) +#if U8G_SPI_USE_MODE_3 #define SPISEND_SW_DUE u8g_spiSend_sw_DUE_mode_3 #else #define SPISEND_SW_DUE u8g_spiSend_sw_DUE_mode_0 @@ -96,15 +96,15 @@ uint8_t u8g_com_HAL_DUE_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void break; case U8G_COM_MSG_CHIP_SELECT: - #if ENABLED(FYSETC_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel_DUE(u8g, U8G_PI_SCK, 1); //set SCK to mode 3 idle state before CS goes active + #if U8G_SPI_USE_MODE_3 // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel_DUE(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel_DUE(u8g, U8G_PI_CS, LOW); } else { u8g_SetPILevel_DUE(u8g, U8G_PI_CS, HIGH); - u8g_SetPILevel_DUE(u8g, U8G_PI_SCK, 0); //set SCK to mode 0 idle state after CS goes inactive + u8g_SetPILevel_DUE(u8g, U8G_PI_SCK, 0); // Set SCK to mode 0 idle state after CS goes inactive } #else u8g_SetPILevel_DUE(u8g, U8G_PI_CS, !arg_val); diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp b/Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_sw_spi_shared.cpp similarity index 98% rename from Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp rename to Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_sw_spi_shared.cpp index 904924793b..86c8a48470 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp +++ b/Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_sw_spi_shared.cpp @@ -81,7 +81,7 @@ Pio *SCK_pPio, *MOSI_pPio; uint32_t SCK_dwMask, MOSI_dwMask; void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (val & 0x80) MOSI_pPio->PIO_SODR = MOSI_dwMask; else @@ -95,7 +95,7 @@ void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz } void u8g_spiSend_sw_DUE_mode_3(uint8_t val) { // 3.5MHz - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { SCK_pPio->PIO_CODR = SCK_dwMask; DELAY_NS(50); if (val & 0x80) diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h b/Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_sw_spi_shared.h similarity index 100% rename from Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h rename to Marlin/src/HAL/DUE/u8g/u8g_com_HAL_DUE_sw_spi_shared.h diff --git a/Marlin/src/HAL/DUE/upload_extra_script.py b/Marlin/src/HAL/DUE/upload_extra_script.py index 4f7a494512..729b1d67de 100644 --- a/Marlin/src/HAL/DUE/upload_extra_script.py +++ b/Marlin/src/HAL/DUE/upload_extra_script.py @@ -6,14 +6,14 @@ # import pioutil if pioutil.is_pio_build(): - import platform - current_OS = platform.system() + import platform + current_OS = platform.system() - if current_OS == 'Windows': + if current_OS == 'Windows': - Import("env") + env = pioutil.env - # Use bossac.exe on Windows - env.Replace( - UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot $SOURCE" - ) + # Use bossac.exe on Windows + env.Replace( + UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot $SOURCE" + ) diff --git a/Marlin/src/HAL/DUE/usb/.editorconfig b/Marlin/src/HAL/DUE/usb/.editorconfig new file mode 100644 index 0000000000..f2c26de5ee --- /dev/null +++ b/Marlin/src/HAL/DUE/usb/.editorconfig @@ -0,0 +1,5 @@ +# editorconfig.org + +[{*.c,*.cpp,*.h}] +indent_style = tab +indent_size = 4 diff --git a/Marlin/src/HAL/DUE/usb/README.md b/Marlin/src/HAL/DUE/usb/README.md new file mode 100644 index 0000000000..2548135aca --- /dev/null +++ b/Marlin/src/HAL/DUE/usb/README.md @@ -0,0 +1,29 @@ +# USB Files Source Documentation + +## Source + +We sourced the USB files in Marlin from the Atmel ASF (Advanced Software Framework). The framework provides a variety of examples which were utilized in this project. + +Atmel doesn't provide these files in a source repository but they can be extracted from ASF, which can be downloaded from Atmel. + +[Advanced Software Framework](https://www.microchip.com/en-us/tools-resources/develop/libraries/advanced-software-framework) + +## Modifications + +The files are mostly unmodified except for minor cosmetic changes but some more significant changes were needed. + +The changes that prompted the addition of this README file are listed below. Other changes may have been made prior to this. + +1. Modified `uotghs_device_due.c` to resolve race conditions that could leave interrupts asserted when freezing the peripheral clock, resulting in hangs and watchdog resets due to the ensuing interrupt storm. + +## Version Information + +We don't know the exact version of ASF used as the source. However, the copyright information in the files indicates they are from 2015. + +## Upgrade Considerations + +We looked at the ASF 3.52.0 files released in 2022 but saw no immediate benefits to justify an upgrade. It's important to note that the files in Marlin don't follow the same folder structure as the files in ASF, which complicates the process of comparing and applying updated files. + +When these files are updated it's important to carefully compare them to Marlin's versions so any improvements in the Marlin sources are brought forward. + +It would be best to make Marlin's directory structure align with ASF or at least document the source of each file to ease future updates. diff --git a/Marlin/src/HAL/DUE/usb/compiler.h b/Marlin/src/HAL/DUE/usb/compiler.h index 633197914e..27c554cdb7 100644 --- a/Marlin/src/HAL/DUE/usb/compiler.h +++ b/Marlin/src/HAL/DUE/usb/compiler.h @@ -142,7 +142,6 @@ */ #define COMPILER_PACK_RESET() COMPILER_PRAGMA(pack()) - /** * \brief Set aligned boundary. */ @@ -283,7 +282,6 @@ typedef double F64; //!< 64-bit floating-point number. typedef uint32_t iram_size_t; //! @} - /*! \name Status Types */ //! @{ @@ -291,7 +289,6 @@ typedef bool Status_bool_t; //!< Boolean status. typedef U8 Status_t; //!< 8-bit-coded status. //! @} - /*! \name Aliasing Aggregate Types */ //! @{ @@ -462,7 +459,6 @@ typedef struct #endif //! @} - #ifndef __ASSEMBLY__ // not for assembling. //! \name Optimization Control @@ -581,7 +577,6 @@ typedef struct //! @} - /*! \name Zero-Bit Counting * * Under GCC, __builtin_clz and __builtin_ctz behave like macros when @@ -692,7 +687,6 @@ typedef struct //! @} - /*! \name Bit Reversing */ //! @{ @@ -732,7 +726,6 @@ typedef struct //! @} - /*! \name Alignment */ //! @{ @@ -798,7 +791,6 @@ typedef struct */ #define Long_call(addr) ((*(void (*)(void))(addr))()) - /*! \name MCU Endianism Handling * ARM is MCU little endianism. */ @@ -868,7 +860,6 @@ typedef struct #define CPU_TO_BE32(x) swap32(x) //! @} - /*! \name Endianism Conversion * * The same considerations as for clz and ctz apply here but GCC's @@ -955,7 +946,6 @@ typedef struct //! @} - /*! \name Target Abstraction */ //! @{ @@ -997,7 +987,6 @@ typedef U8 Byte; //!< 8-bit unsigned integer. #endif // #ifndef __ASSEMBLY__ - #ifdef __ICCARM__ #define SHORTENUM __packed #elif defined(__GNUC__) diff --git a/Marlin/src/HAL/DUE/usb/conf_access.h b/Marlin/src/HAL/DUE/usb/conf_access.h index f401685223..0ea5fe2287 100644 --- a/Marlin/src/HAL/DUE/usb/conf_access.h +++ b/Marlin/src/HAL/DUE/usb/conf_access.h @@ -81,7 +81,6 @@ #define LUN_0_NAME "\"SD/MMC Card\"" //! @} - /*! \name Actions Associated with Memory Accesses * * Write here the action to associate with each memory access. @@ -112,5 +111,4 @@ #define GLOBAL_WR_PROTECT false //!< Management of a global write protection. //! @} - #endif // _CONF_ACCESS_H_ diff --git a/Marlin/src/HAL/DUE/usb/conf_clock.h b/Marlin/src/HAL/DUE/usb/conf_clock.h index 97e70e99a5..0c7815ee4d 100644 --- a/Marlin/src/HAL/DUE/usb/conf_clock.h +++ b/Marlin/src/HAL/DUE/usb/conf_clock.h @@ -96,5 +96,4 @@ // - UPLL frequency: 480MHz // - USB clock: 480 / 1 = 480MHz - #endif /* CONF_CLOCK_H_INCLUDED */ diff --git a/Marlin/src/HAL/DUE/usb/conf_usb.h b/Marlin/src/HAL/DUE/usb/conf_usb.h index 4de9e347e2..fb4ef34241 100644 --- a/Marlin/src/HAL/DUE/usb/conf_usb.h +++ b/Marlin/src/HAL/DUE/usb/conf_usb.h @@ -88,7 +88,6 @@ #endif //@} - /** * USB Device Callbacks definitions (Optional) * @{ @@ -101,7 +100,7 @@ #define USB_DEVICE_SPECIFIC_REQUEST() usb_task_other_requests() //@} -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA /** * USB Device low level configuration * When only one interface is used, these configurations are defined by the class module. @@ -150,7 +149,6 @@ //@} - /** * USB Interface Configuration * @{ @@ -185,7 +183,7 @@ //! Enable id string of interface to add an extra USB string #define UDI_CDC_IAD_STRING_ID 4 -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA /** * USB CDC low level configuration * In standalone these configurations are defined by the CDC module. @@ -210,7 +208,6 @@ //@} //@} - /** * Configuration of MSC interface * @{ @@ -245,7 +242,6 @@ //@} - /** * Description of Composite Device * @{ diff --git a/Marlin/src/HAL/DUE/usb/ctrl_access.c b/Marlin/src/HAL/DUE/usb/ctrl_access.c index 99f97f62cb..ec0e4adc4b 100644 --- a/Marlin/src/HAL/DUE/usb/ctrl_access.c +++ b/Marlin/src/HAL/DUE/usb/ctrl_access.c @@ -63,12 +63,11 @@ #include "compiler.h" #include "preprocessor.h" #ifdef FREERTOS_USED -#include "FreeRTOS.h" -#include "semphr.h" +#include +#include #endif #include "ctrl_access.h" - //_____ D E F I N I T I O N S ______________________________________________ #ifdef FREERTOS_USED @@ -112,7 +111,6 @@ static xSemaphoreHandle ctrl_access_semphr = NULL; #endif // FREERTOS_USED - #if MAX_LUN /*! \brief Initializes an entry of the LUN descriptor table. @@ -242,17 +240,14 @@ static const struct #endif - #if GLOBAL_WR_PROTECT == true bool g_wr_protect; #endif - /*! \name Control Interface */ //! @{ - #ifdef FREERTOS_USED bool ctrl_access_init(void) @@ -270,7 +265,6 @@ bool ctrl_access_init(void) return true; } - /*! \brief Locks accesses to LUNs. * * \return \c true if the access was successfully locked, else \c false. @@ -288,7 +282,6 @@ static bool ctrl_access_lock(void) #endif // FREERTOS_USED - U8 get_nb_lun(void) { #if MEM_USB == ENABLE @@ -309,13 +302,11 @@ U8 get_nb_lun(void) #endif } - U8 get_cur_lun(void) { return LUN_ID_0; } - Ctrl_status mem_test_unit_ready(U8 lun) { Ctrl_status status; @@ -337,7 +328,6 @@ Ctrl_status mem_test_unit_ready(U8 lun) return status; } - Ctrl_status mem_read_capacity(U8 lun, U32 *u32_nb_sector) { Ctrl_status status; @@ -359,7 +349,6 @@ Ctrl_status mem_read_capacity(U8 lun, U32 *u32_nb_sector) return status; } - U8 mem_sector_size(U8 lun) { U8 sector_size; @@ -381,7 +370,6 @@ U8 mem_sector_size(U8 lun) return sector_size; } - bool mem_unload(U8 lun, bool unload) { bool unloaded; @@ -433,7 +421,6 @@ bool mem_wr_protect(U8 lun) return wr_protect; } - bool mem_removal(U8 lun) { bool removal; @@ -458,7 +445,6 @@ bool mem_removal(U8 lun) return removal; } - const char *mem_name(U8 lun) { #if MAX_LUN==0 @@ -475,17 +461,14 @@ const char *mem_name(U8 lun) #endif } - //! @} - #if ACCESS_USB == true /*! \name MEM <-> USB Interface */ //! @{ - Ctrl_status memory_2_usb(U8 lun, U32 addr, U16 nb_sector) { Ctrl_status status; @@ -505,7 +488,6 @@ Ctrl_status memory_2_usb(U8 lun, U32 addr, U16 nb_sector) return status; } - Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector) { Ctrl_status status; @@ -525,19 +507,16 @@ Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector) return status; } - //! @} #endif // ACCESS_USB == true - #if ACCESS_MEM_TO_RAM == true /*! \name MEM <-> RAM Interface */ //! @{ - Ctrl_status memory_2_ram(U8 lun, U32 addr, void *ram) { Ctrl_status status; @@ -564,7 +543,6 @@ Ctrl_status memory_2_ram(U8 lun, U32 addr, void *ram) return status; } - Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram) { Ctrl_status status; @@ -591,19 +569,16 @@ Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram) return status; } - //! @} #endif // ACCESS_MEM_TO_RAM == true - #if ACCESS_STREAM == true /*! \name Streaming MEM <-> MEM Interface */ //! @{ - #if ACCESS_MEM_TO_MEM == true #include "fat.h" @@ -625,21 +600,18 @@ Ctrl_status stream_mem_to_mem(U8 src_lun, U32 src_addr, U8 dest_lun, U32 dest_ad #endif // ACCESS_MEM_TO_MEM == true - Ctrl_status stream_state(U8 id) { UNUSED(id); return CTRL_GOOD; } - U16 stream_stop(U8 id) { UNUSED(id); return 0; } - //! @} #endif // ACCESS_STREAM diff --git a/Marlin/src/HAL/DUE/usb/ctrl_access.h b/Marlin/src/HAL/DUE/usb/ctrl_access.h index b33839076e..d9cb05da74 100644 --- a/Marlin/src/HAL/DUE/usb/ctrl_access.h +++ b/Marlin/src/HAL/DUE/usb/ctrl_access.h @@ -56,7 +56,6 @@ * Support and FAQ: visit Atmel Support */ - #ifndef _CTRL_ACCESS_H_ #define _CTRL_ACCESS_H_ @@ -89,7 +88,6 @@ typedef enum CTRL_BUSY = FAIL + 2 //!< Memory not initialized or changed. } Ctrl_status; - // FYI: Each Logical Unit Number (LUN) corresponds to a memory. // Check LUN defines. @@ -136,7 +134,6 @@ typedef enum #define LUN_ID_USB (MAX_LUN) //!< First dynamic LUN (USB host mass storage). //! @} - // Include LUN header files. #if LUN_0 == ENABLE #include LUN_0_INCLUDE @@ -166,13 +163,11 @@ typedef enum #include LUN_USB_INCLUDE #endif - // Check the configuration of write protection in conf_access.h. #ifndef GLOBAL_WR_PROTECT #error GLOBAL_WR_PROTECT must be defined as true or false in conf_access.h #endif - #if GLOBAL_WR_PROTECT == true //! Write protect. @@ -180,7 +175,6 @@ extern bool g_wr_protect; #endif - /*! \name Control Interface */ //! @{ @@ -279,7 +273,6 @@ extern const char *mem_name(U8 lun); //! @} - #if ACCESS_USB == true /*! \name MEM <-> USB Interface @@ -310,7 +303,6 @@ extern Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector); #endif // ACCESS_USB == true - #if ACCESS_MEM_TO_RAM == true /*! \name MEM <-> RAM Interface @@ -341,7 +333,6 @@ extern Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram); #endif // ACCESS_MEM_TO_RAM == true - #if ACCESS_STREAM == true /*! \name Streaming MEM <-> MEM Interface diff --git a/Marlin/src/HAL/DUE/usb/genclk.h b/Marlin/src/HAL/DUE/usb/genclk.h index cde03bc0d1..45eba5873f 100644 --- a/Marlin/src/HAL/DUE/usb/genclk.h +++ b/Marlin/src/HAL/DUE/usb/genclk.h @@ -74,17 +74,17 @@ extern "C" { //@{ enum genclk_source { - GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock - GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock - GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock - GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock - GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock + GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock + GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock + GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock + GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock + GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock }; //@} @@ -93,176 +93,162 @@ enum genclk_source { //@{ enum genclk_divider { - GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1 - GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2 - GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4 - GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8 - GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16 - GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32 - GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64 + GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1 + GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2 + GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4 + GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8 + GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16 + GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32 + GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64 }; //@} struct genclk_config { - uint32_t ctrl; + uint32_t ctrl; }; -static inline void genclk_config_defaults(struct genclk_config *p_cfg, - uint32_t ul_id) -{ - ul_id = ul_id; - p_cfg->ctrl = 0; +static inline void genclk_config_defaults(struct genclk_config *p_cfg, uint32_t ul_id) { + ul_id = ul_id; + p_cfg->ctrl = 0; } -static inline void genclk_config_read(struct genclk_config *p_cfg, - uint32_t ul_id) -{ - p_cfg->ctrl = PMC->PMC_PCK[ul_id]; +static inline void genclk_config_read(struct genclk_config *p_cfg, uint32_t ul_id) { + p_cfg->ctrl = PMC->PMC_PCK[ul_id]; } -static inline void genclk_config_write(const struct genclk_config *p_cfg, - uint32_t ul_id) -{ - PMC->PMC_PCK[ul_id] = p_cfg->ctrl; +static inline void genclk_config_write(const struct genclk_config *p_cfg, uint32_t ul_id) { + PMC->PMC_PCK[ul_id] = p_cfg->ctrl; } //! \name Programmable Clock Source and Prescaler configuration //@{ -static inline void genclk_config_set_source(struct genclk_config *p_cfg, - enum genclk_source e_src) -{ - p_cfg->ctrl &= (~PMC_PCK_CSS_Msk); +static inline void genclk_config_set_source(struct genclk_config *p_cfg, enum genclk_source e_src) { + p_cfg->ctrl &= (~PMC_PCK_CSS_Msk); - switch (e_src) { - case GENCLK_PCK_SRC_SLCK_RC: - case GENCLK_PCK_SRC_SLCK_XTAL: - case GENCLK_PCK_SRC_SLCK_BYPASS: - p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK); - break; + switch (e_src) { + case GENCLK_PCK_SRC_SLCK_RC: + case GENCLK_PCK_SRC_SLCK_XTAL: + case GENCLK_PCK_SRC_SLCK_BYPASS: + p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK); + break; - case GENCLK_PCK_SRC_MAINCK_4M_RC: - case GENCLK_PCK_SRC_MAINCK_8M_RC: - case GENCLK_PCK_SRC_MAINCK_12M_RC: - case GENCLK_PCK_SRC_MAINCK_XTAL: - case GENCLK_PCK_SRC_MAINCK_BYPASS: - p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK); - break; + case GENCLK_PCK_SRC_MAINCK_4M_RC: + case GENCLK_PCK_SRC_MAINCK_8M_RC: + case GENCLK_PCK_SRC_MAINCK_12M_RC: + case GENCLK_PCK_SRC_MAINCK_XTAL: + case GENCLK_PCK_SRC_MAINCK_BYPASS: + p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK); + break; - case GENCLK_PCK_SRC_PLLACK: - p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK); - break; + case GENCLK_PCK_SRC_PLLACK: + p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK); + break; - case GENCLK_PCK_SRC_PLLBCK: - p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK); - break; + case GENCLK_PCK_SRC_PLLBCK: + p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK); + break; - case GENCLK_PCK_SRC_MCK: - p_cfg->ctrl |= (PMC_PCK_CSS_MCK); - break; - } + case GENCLK_PCK_SRC_MCK: + p_cfg->ctrl |= (PMC_PCK_CSS_MCK); + break; + } } -static inline void genclk_config_set_divider(struct genclk_config *p_cfg, - uint32_t e_divider) -{ - p_cfg->ctrl &= ~PMC_PCK_PRES_Msk; - p_cfg->ctrl |= e_divider; +static inline void genclk_config_set_divider(struct genclk_config *p_cfg, uint32_t e_divider) { + p_cfg->ctrl &= ~PMC_PCK_PRES_Msk; + p_cfg->ctrl |= e_divider; } //@} -static inline void genclk_enable(const struct genclk_config *p_cfg, - uint32_t ul_id) -{ - PMC->PMC_PCK[ul_id] = p_cfg->ctrl; - pmc_enable_pck(ul_id); +static inline void genclk_enable(const struct genclk_config *p_cfg, uint32_t ul_id) { + PMC->PMC_PCK[ul_id] = p_cfg->ctrl; + pmc_enable_pck(ul_id); } -static inline void genclk_disable(uint32_t ul_id) -{ - pmc_disable_pck(ul_id); +static inline void genclk_disable(uint32_t ul_id) { + pmc_disable_pck(ul_id); } -static inline void genclk_enable_source(enum genclk_source e_src) -{ - switch (e_src) { - case GENCLK_PCK_SRC_SLCK_RC: - if (!osc_is_ready(OSC_SLCK_32K_RC)) { - osc_enable(OSC_SLCK_32K_RC); - osc_wait_ready(OSC_SLCK_32K_RC); - } - break; +static inline void genclk_enable_source(enum genclk_source e_src) { + switch (e_src) { + case GENCLK_PCK_SRC_SLCK_RC: + if (!osc_is_ready(OSC_SLCK_32K_RC)) { + osc_enable(OSC_SLCK_32K_RC); + osc_wait_ready(OSC_SLCK_32K_RC); + } + break; - case GENCLK_PCK_SRC_SLCK_XTAL: - if (!osc_is_ready(OSC_SLCK_32K_XTAL)) { - osc_enable(OSC_SLCK_32K_XTAL); - osc_wait_ready(OSC_SLCK_32K_XTAL); - } - break; + case GENCLK_PCK_SRC_SLCK_XTAL: + if (!osc_is_ready(OSC_SLCK_32K_XTAL)) { + osc_enable(OSC_SLCK_32K_XTAL); + osc_wait_ready(OSC_SLCK_32K_XTAL); + } + break; - case GENCLK_PCK_SRC_SLCK_BYPASS: - if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) { - osc_enable(OSC_SLCK_32K_BYPASS); - osc_wait_ready(OSC_SLCK_32K_BYPASS); - } - break; + case GENCLK_PCK_SRC_SLCK_BYPASS: + if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) { + osc_enable(OSC_SLCK_32K_BYPASS); + osc_wait_ready(OSC_SLCK_32K_BYPASS); + } + break; - case GENCLK_PCK_SRC_MAINCK_4M_RC: - if (!osc_is_ready(OSC_MAINCK_4M_RC)) { - osc_enable(OSC_MAINCK_4M_RC); - osc_wait_ready(OSC_MAINCK_4M_RC); - } - break; + case GENCLK_PCK_SRC_MAINCK_4M_RC: + if (!osc_is_ready(OSC_MAINCK_4M_RC)) { + osc_enable(OSC_MAINCK_4M_RC); + osc_wait_ready(OSC_MAINCK_4M_RC); + } + break; - case GENCLK_PCK_SRC_MAINCK_8M_RC: - if (!osc_is_ready(OSC_MAINCK_8M_RC)) { - osc_enable(OSC_MAINCK_8M_RC); - osc_wait_ready(OSC_MAINCK_8M_RC); - } - break; + case GENCLK_PCK_SRC_MAINCK_8M_RC: + if (!osc_is_ready(OSC_MAINCK_8M_RC)) { + osc_enable(OSC_MAINCK_8M_RC); + osc_wait_ready(OSC_MAINCK_8M_RC); + } + break; - case GENCLK_PCK_SRC_MAINCK_12M_RC: - if (!osc_is_ready(OSC_MAINCK_12M_RC)) { - osc_enable(OSC_MAINCK_12M_RC); - osc_wait_ready(OSC_MAINCK_12M_RC); - } - break; + case GENCLK_PCK_SRC_MAINCK_12M_RC: + if (!osc_is_ready(OSC_MAINCK_12M_RC)) { + osc_enable(OSC_MAINCK_12M_RC); + osc_wait_ready(OSC_MAINCK_12M_RC); + } + break; - case GENCLK_PCK_SRC_MAINCK_XTAL: - if (!osc_is_ready(OSC_MAINCK_XTAL)) { - osc_enable(OSC_MAINCK_XTAL); - osc_wait_ready(OSC_MAINCK_XTAL); - } - break; + case GENCLK_PCK_SRC_MAINCK_XTAL: + if (!osc_is_ready(OSC_MAINCK_XTAL)) { + osc_enable(OSC_MAINCK_XTAL); + osc_wait_ready(OSC_MAINCK_XTAL); + } + break; - case GENCLK_PCK_SRC_MAINCK_BYPASS: - if (!osc_is_ready(OSC_MAINCK_BYPASS)) { - osc_enable(OSC_MAINCK_BYPASS); - osc_wait_ready(OSC_MAINCK_BYPASS); - } - break; + case GENCLK_PCK_SRC_MAINCK_BYPASS: + if (!osc_is_ready(OSC_MAINCK_BYPASS)) { + osc_enable(OSC_MAINCK_BYPASS); + osc_wait_ready(OSC_MAINCK_BYPASS); + } + break; -#ifdef CONFIG_PLL0_SOURCE - case GENCLK_PCK_SRC_PLLACK: - pll_enable_config_defaults(0); - break; -#endif + #ifdef CONFIG_PLL0_SOURCE + case GENCLK_PCK_SRC_PLLACK: + pll_enable_config_defaults(0); + break; + #endif -#ifdef CONFIG_PLL1_SOURCE - case GENCLK_PCK_SRC_PLLBCK: - pll_enable_config_defaults(1); - break; -#endif + #ifdef CONFIG_PLL1_SOURCE + case GENCLK_PCK_SRC_PLLBCK: + pll_enable_config_defaults(1); + break; + #endif - case GENCLK_PCK_SRC_MCK: - break; + case GENCLK_PCK_SRC_MCK: + break; - default: - Assert(false); - break; - } + default: + Assert(false); + break; + } } //! @} diff --git a/Marlin/src/HAL/DUE/usb/mrepeat.h b/Marlin/src/HAL/DUE/usb/mrepeat.h index 8363d9cde3..10a8237545 100644 --- a/Marlin/src/HAL/DUE/usb/mrepeat.h +++ b/Marlin/src/HAL/DUE/usb/mrepeat.h @@ -57,7 +57,6 @@ #include "preprocessor.h" - //! Maximal number of repetitions supported by MREPEAT. #define MREPEAT_LIMIT 256 diff --git a/Marlin/src/HAL/DUE/usb/osc.h b/Marlin/src/HAL/DUE/usb/osc.h index 953bcbbed1..1585018ed8 100644 --- a/Marlin/src/HAL/DUE/usb/osc.h +++ b/Marlin/src/HAL/DUE/usb/osc.h @@ -62,28 +62,28 @@ extern "C" { * should be defined by the board code, otherwise default value are used. */ #ifndef BOARD_FREQ_SLCK_XTAL -# warning The board slow clock xtal frequency has not been defined. -# define BOARD_FREQ_SLCK_XTAL (32768UL) + #warning The board slow clock xtal frequency has not been defined. + #define BOARD_FREQ_SLCK_XTAL (32768UL) #endif #ifndef BOARD_FREQ_SLCK_BYPASS -# warning The board slow clock bypass frequency has not been defined. -# define BOARD_FREQ_SLCK_BYPASS (32768UL) + #warning The board slow clock bypass frequency has not been defined. + #define BOARD_FREQ_SLCK_BYPASS (32768UL) #endif #ifndef BOARD_FREQ_MAINCK_XTAL -# warning The board main clock xtal frequency has not been defined. -# define BOARD_FREQ_MAINCK_XTAL (12000000UL) + #warning The board main clock xtal frequency has not been defined. + #define BOARD_FREQ_MAINCK_XTAL (12000000UL) #endif #ifndef BOARD_FREQ_MAINCK_BYPASS -# warning The board main clock bypass frequency has not been defined. -# define BOARD_FREQ_MAINCK_BYPASS (12000000UL) + #warning The board main clock bypass frequency has not been defined. + #define BOARD_FREQ_MAINCK_BYPASS (12000000UL) #endif #ifndef BOARD_OSC_STARTUP_US -# warning The board main clock xtal startup time has not been defined. -# define BOARD_OSC_STARTUP_US (15625UL) + #warning The board main clock xtal startup time has not been defined. + #define BOARD_OSC_STARTUP_US (15625UL) #endif /** @@ -115,122 +115,116 @@ extern "C" { #define OSC_MAINCK_BYPASS_HZ BOARD_FREQ_MAINCK_BYPASS //!< External bypass oscillator. //@} -static inline void osc_enable(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - break; +static inline void osc_enable(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + break; - case OSC_SLCK_32K_XTAL: - pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL); - break; + case OSC_SLCK_32K_XTAL: + pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL); + break; - case OSC_SLCK_32K_BYPASS: - pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS); - break; + case OSC_SLCK_32K_BYPASS: + pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS); + break; + case OSC_MAINCK_4M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz); + break; - case OSC_MAINCK_4M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz); - break; + case OSC_MAINCK_8M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz); + break; - case OSC_MAINCK_8M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz); - break; + case OSC_MAINCK_12M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz); + break; - case OSC_MAINCK_12M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz); - break; + case OSC_MAINCK_XTAL: + pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*, + pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, + OSC_SLCK_32K_RC_HZ)*/); + break; - - case OSC_MAINCK_XTAL: - pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*, - pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, - OSC_SLCK_32K_RC_HZ)*/); - break; - - case OSC_MAINCK_BYPASS: - pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*, - pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, - OSC_SLCK_32K_RC_HZ)*/); - break; - } + case OSC_MAINCK_BYPASS: + pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*, + pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, + OSC_SLCK_32K_RC_HZ)*/); + break; + } } -static inline void osc_disable(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - case OSC_SLCK_32K_XTAL: - case OSC_SLCK_32K_BYPASS: - break; +static inline void osc_disable(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + case OSC_SLCK_32K_XTAL: + case OSC_SLCK_32K_BYPASS: + break; - case OSC_MAINCK_4M_RC: - case OSC_MAINCK_8M_RC: - case OSC_MAINCK_12M_RC: - pmc_osc_disable_fastrc(); - break; + case OSC_MAINCK_4M_RC: + case OSC_MAINCK_8M_RC: + case OSC_MAINCK_12M_RC: + pmc_osc_disable_fastrc(); + break; - case OSC_MAINCK_XTAL: - pmc_osc_disable_xtal(PMC_OSC_XTAL); - break; + case OSC_MAINCK_XTAL: + pmc_osc_disable_xtal(PMC_OSC_XTAL); + break; - case OSC_MAINCK_BYPASS: - pmc_osc_disable_xtal(PMC_OSC_BYPASS); - break; - } + case OSC_MAINCK_BYPASS: + pmc_osc_disable_xtal(PMC_OSC_BYPASS); + break; + } } -static inline bool osc_is_ready(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - return 1; +static inline bool osc_is_ready(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + return 1; - case OSC_SLCK_32K_XTAL: - case OSC_SLCK_32K_BYPASS: - return pmc_osc_is_ready_32kxtal(); + case OSC_SLCK_32K_XTAL: + case OSC_SLCK_32K_BYPASS: + return pmc_osc_is_ready_32kxtal(); - case OSC_MAINCK_4M_RC: - case OSC_MAINCK_8M_RC: - case OSC_MAINCK_12M_RC: - case OSC_MAINCK_XTAL: - case OSC_MAINCK_BYPASS: - return pmc_osc_is_ready_mainck(); - } + case OSC_MAINCK_4M_RC: + case OSC_MAINCK_8M_RC: + case OSC_MAINCK_12M_RC: + case OSC_MAINCK_XTAL: + case OSC_MAINCK_BYPASS: + return pmc_osc_is_ready_mainck(); + } - return 0; + return 0; } -static inline uint32_t osc_get_rate(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - return OSC_SLCK_32K_RC_HZ; +static inline uint32_t osc_get_rate(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + return OSC_SLCK_32K_RC_HZ; - case OSC_SLCK_32K_XTAL: - return BOARD_FREQ_SLCK_XTAL; + case OSC_SLCK_32K_XTAL: + return BOARD_FREQ_SLCK_XTAL; - case OSC_SLCK_32K_BYPASS: - return BOARD_FREQ_SLCK_BYPASS; + case OSC_SLCK_32K_BYPASS: + return BOARD_FREQ_SLCK_BYPASS; - case OSC_MAINCK_4M_RC: - return OSC_MAINCK_4M_RC_HZ; + case OSC_MAINCK_4M_RC: + return OSC_MAINCK_4M_RC_HZ; - case OSC_MAINCK_8M_RC: - return OSC_MAINCK_8M_RC_HZ; + case OSC_MAINCK_8M_RC: + return OSC_MAINCK_8M_RC_HZ; - case OSC_MAINCK_12M_RC: - return OSC_MAINCK_12M_RC_HZ; + case OSC_MAINCK_12M_RC: + return OSC_MAINCK_12M_RC_HZ; - case OSC_MAINCK_XTAL: - return BOARD_FREQ_MAINCK_XTAL; + case OSC_MAINCK_XTAL: + return BOARD_FREQ_MAINCK_XTAL; - case OSC_MAINCK_BYPASS: - return BOARD_FREQ_MAINCK_BYPASS; - } + case OSC_MAINCK_BYPASS: + return BOARD_FREQ_MAINCK_BYPASS; + } - return 0; + return 0; } /** @@ -241,11 +235,10 @@ static inline uint32_t osc_get_rate(uint32_t ul_id) * * \param id A number identifying the oscillator to wait for. */ -static inline void osc_wait_ready(uint8_t id) -{ - while (!osc_is_ready(id)) { - /* Do nothing */ - } +static inline void osc_wait_ready(uint8_t id) { + while (!osc_is_ready(id)) { + /* Do nothing */ + } } //! @} diff --git a/Marlin/src/HAL/DUE/usb/pll.h b/Marlin/src/HAL/DUE/usb/pll.h index 8eaf27672b..d25a1f65d0 100644 --- a/Marlin/src/HAL/DUE/usb/pll.h +++ b/Marlin/src/HAL/DUE/usb/pll.h @@ -77,22 +77,22 @@ extern "C" { #define PLL_COUNT 0x3FU enum pll_source { - PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator. - PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator. - PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator. - PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator. - PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator. - PLL_NR_SOURCES, //!< Number of PLL sources. + PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator. + PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator. + PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator. + PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator. + PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator. + PLL_NR_SOURCES, //!< Number of PLL sources. }; struct pll_config { - uint32_t ctrl; + uint32_t ctrl; }; #define pll_get_default_rate(pll_id) \ - ((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \ - * CONFIG_PLL##pll_id##_MUL) \ - / CONFIG_PLL##pll_id##_DIV) + ((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \ + * CONFIG_PLL##pll_id##_MUL) \ + / CONFIG_PLL##pll_id##_DIV) /* Force UTMI PLL parameters (Hardware defined) */ #ifdef CONFIG_PLL1_SOURCE @@ -113,145 +113,130 @@ struct pll_config { * is hidden in this implementation. Use mul as mul effective value. */ static inline void pll_config_init(struct pll_config *p_cfg, - enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul) -{ - uint32_t vco_hz; + enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul) { + uint32_t vco_hz; - Assert(e_src < PLL_NR_SOURCES); + Assert(e_src < PLL_NR_SOURCES); - if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */ - p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT); - } else { /* PLLA */ - /* Calculate internal VCO frequency */ - vco_hz = osc_get_rate(e_src) / ul_div; - Assert(vco_hz >= PLL_INPUT_MIN_HZ); - Assert(vco_hz <= PLL_INPUT_MAX_HZ); + if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */ + p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT); + } + else { /* PLLA */ + /* Calculate internal VCO frequency */ + vco_hz = osc_get_rate(e_src) / ul_div; + Assert(vco_hz >= PLL_INPUT_MIN_HZ); + Assert(vco_hz <= PLL_INPUT_MAX_HZ); - vco_hz *= ul_mul; - Assert(vco_hz >= PLL_OUTPUT_MIN_HZ); - Assert(vco_hz <= PLL_OUTPUT_MAX_HZ); + vco_hz *= ul_mul; + Assert(vco_hz >= PLL_OUTPUT_MIN_HZ); + Assert(vco_hz <= PLL_OUTPUT_MAX_HZ); - /* PMC hardware will automatically make it mul+1 */ - p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT); - } + /* PMC hardware will automatically make it mul+1 */ + p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT); + } } -#define pll_config_defaults(cfg, pll_id) \ - pll_config_init(cfg, \ - CONFIG_PLL##pll_id##_SOURCE, \ - CONFIG_PLL##pll_id##_DIV, \ - CONFIG_PLL##pll_id##_MUL) +#define pll_config_defaults(cfg, pll_id) \ + pll_config_init(cfg, \ + CONFIG_PLL##pll_id##_SOURCE, \ + CONFIG_PLL##pll_id##_DIV, \ + CONFIG_PLL##pll_id##_MUL) -static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); - - if (ul_pll_id == PLLA_ID) { - p_cfg->ctrl = PMC->CKGR_PLLAR; - } else { - p_cfg->ctrl = PMC->CKGR_UCKR; - } +static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); + p_cfg->ctrl = ul_pll_id == PLLA_ID ? PMC->CKGR_PLLAR : PMC->CKGR_UCKR; } -static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); // Always stop PLL first! - PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; - } else { - PMC->CKGR_UCKR = p_cfg->ctrl; - } + if (ul_pll_id == PLLA_ID) { + pmc_disable_pllack(); // Always stop PLL first! + PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; + } + else + PMC->CKGR_UCKR = p_cfg->ctrl; } -static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); // Always stop PLL first! - PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; - } else { - PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN; - } + if (ul_pll_id == PLLA_ID) { + pmc_disable_pllack(); // Always stop PLL first! + PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; + } + else + PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN; } /** * \note This will only disable the selected PLL, not the underlying oscillator (mainck). */ -static inline void pll_disable(uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_disable(uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); - } else { - PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN; - } + if (ul_pll_id == PLLA_ID) + pmc_disable_pllack(); + else + PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN; } -static inline uint32_t pll_is_locked(uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline uint32_t pll_is_locked(uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - return pmc_is_locked_pllack(); - } else { - return pmc_is_locked_upll(); - } + if (ul_pll_id == PLLA_ID) + return pmc_is_locked_pllack(); + else + return pmc_is_locked_upll(); } -static inline void pll_enable_source(enum pll_source e_src) -{ - switch (e_src) { - case PLL_SRC_MAINCK_4M_RC: - case PLL_SRC_MAINCK_8M_RC: - case PLL_SRC_MAINCK_12M_RC: - case PLL_SRC_MAINCK_XTAL: - case PLL_SRC_MAINCK_BYPASS: - osc_enable(e_src); - osc_wait_ready(e_src); - break; +static inline void pll_enable_source(enum pll_source e_src) { + switch (e_src) { + case PLL_SRC_MAINCK_4M_RC: + case PLL_SRC_MAINCK_8M_RC: + case PLL_SRC_MAINCK_12M_RC: + case PLL_SRC_MAINCK_XTAL: + case PLL_SRC_MAINCK_BYPASS: + osc_enable(e_src); + osc_wait_ready(e_src); + break; - default: - Assert(false); - break; - } + default: + Assert(false); + break; + } } -static inline void pll_enable_config_defaults(unsigned int ul_pll_id) -{ - struct pll_config pllcfg; +static inline void pll_enable_config_defaults(unsigned int ul_pll_id) { + struct pll_config pllcfg; - if (pll_is_locked(ul_pll_id)) { - return; // Pll already running - } - switch (ul_pll_id) { -#ifdef CONFIG_PLL0_SOURCE - case 0: - pll_enable_source(CONFIG_PLL0_SOURCE); - pll_config_init(&pllcfg, - CONFIG_PLL0_SOURCE, - CONFIG_PLL0_DIV, - CONFIG_PLL0_MUL); - break; -#endif -#ifdef CONFIG_PLL1_SOURCE - case 1: - pll_enable_source(CONFIG_PLL1_SOURCE); - pll_config_init(&pllcfg, - CONFIG_PLL1_SOURCE, - CONFIG_PLL1_DIV, - CONFIG_PLL1_MUL); - break; -#endif - default: - Assert(false); - break; - } - pll_enable(&pllcfg, ul_pll_id); - while (!pll_is_locked(ul_pll_id)); + if (pll_is_locked(ul_pll_id)) return; // Pll already running + + switch (ul_pll_id) { + #ifdef CONFIG_PLL0_SOURCE + case 0: + pll_enable_source(CONFIG_PLL0_SOURCE); + pll_config_init(&pllcfg, + CONFIG_PLL0_SOURCE, + CONFIG_PLL0_DIV, + CONFIG_PLL0_MUL); + break; + #endif + #ifdef CONFIG_PLL1_SOURCE + case 1: + pll_enable_source(CONFIG_PLL1_SOURCE); + pll_config_init(&pllcfg, + CONFIG_PLL1_SOURCE, + CONFIG_PLL1_DIV, + CONFIG_PLL1_MUL); + break; + #endif + default: + Assert(false); + break; + } + pll_enable(&pllcfg, ul_pll_id); + while (!pll_is_locked(ul_pll_id)); } /** @@ -264,15 +249,12 @@ static inline void pll_enable_config_defaults(unsigned int ul_pll_id) * \retval STATUS_OK The PLL is now locked. * \retval ERR_TIMEOUT Timed out waiting for PLL to become locked. */ -static inline int pll_wait_for_lock(unsigned int pll_id) -{ - Assert(pll_id < NR_PLLS); +static inline int pll_wait_for_lock(unsigned int pll_id) { + Assert(pll_id < NR_PLLS); - while (!pll_is_locked(pll_id)) { - /* Do nothing */ - } + while (!pll_is_locked(pll_id)) { /* Do nothing */ } - return 0; + return 0; } //! @} diff --git a/Marlin/src/HAL/DUE/usb/preprocessor.h b/Marlin/src/HAL/DUE/usb/preprocessor.h index c12d01cb64..fe796c4fb8 100644 --- a/Marlin/src/HAL/DUE/usb/preprocessor.h +++ b/Marlin/src/HAL/DUE/usb/preprocessor.h @@ -51,5 +51,4 @@ #include "stringz.h" #include "mrepeat.h" - #endif // _PREPROCESSOR_H_ diff --git a/Marlin/src/HAL/DUE/usb/sbc_protocol.h b/Marlin/src/HAL/DUE/usb/sbc_protocol.h index ab845739fd..cdd4caa3cd 100644 --- a/Marlin/src/HAL/DUE/usb/sbc_protocol.h +++ b/Marlin/src/HAL/DUE/usb/sbc_protocol.h @@ -57,7 +57,6 @@ #ifndef _SBC_PROTOCOL_H_ #define _SBC_PROTOCOL_H_ - /** * \ingroup usb_msc_protocol * \defgroup usb_sbc_protocol SCSI Block Commands protocol definitions @@ -81,82 +80,81 @@ //@{ enum scsi_sbc_mode { - SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page - SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page - SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page - SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page + SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page + SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page + SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page + SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page }; - //! \name SBC-2 Device-Specific Parameter //@{ -#define SCSI_MS_SBC_WP 0x80 //!< Write Protected -#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported +#define SCSI_MS_SBC_WP 0x80 //!< Write Protected +#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported //@} /** * \brief SBC-2 Short LBA mode parameter block descriptor */ struct sbc_slba_block_desc { - be32_t nr_blocks; //!< Number of Blocks - be32_t block_len; //!< Block Length -#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits + be32_t nr_blocks; //!< Number of Blocks + be32_t block_len; //!< Block Length +#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits }; /** * \brief SBC-2 Caching mode page */ struct sbc_caching_mode_page { - uint8_t page_code; - uint8_t page_length; - uint8_t flags2; -#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control -#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch -#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted -#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity -#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable -#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable -#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor -#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable - uint8_t retention; - be16_t dis_pf_transfer_len; - be16_t min_prefetch; - be16_t max_prefetch; - be16_t max_prefetch_ceil; - uint8_t flags12; -#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write -#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz -#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead -#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable - uint8_t nr_cache_segments; - be16_t cache_segment_size; - uint8_t reserved[4]; + uint8_t page_code; + uint8_t page_length; + uint8_t flags2; +#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control +#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch +#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted +#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity +#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable +#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable +#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor +#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable + uint8_t retention; + be16_t dis_pf_transfer_len; + be16_t min_prefetch; + be16_t max_prefetch; + be16_t max_prefetch_ceil; + uint8_t flags12; +#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write +#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz +#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead +#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable + uint8_t nr_cache_segments; + be16_t cache_segment_size; + uint8_t reserved[4]; }; /** * \brief SBC-2 Read-Write Error Recovery mode page */ struct sbc_rdwr_error_recovery_mode_page { - uint8_t page_code; - uint8_t page_length; -#define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A - uint8_t flags1; -#define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7) -#define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6) -#define SBC_MP_RW_ERR_RECOV_TB (1 << 5) -#define SBC_MP_RW_ERR_RECOV_RC (1 << 4) -#define SBC_MP_RW_ERR_RECOV_ERR (1 << 3) -#define SBC_MP_RW_ERR_RECOV_PER (1 << 2) -#define SBC_MP_RW_ERR_RECOV_DTE (1 << 1) -#define SBC_MP_RW_ERR_RECOV_DCR (1 << 0) - uint8_t read_retry_count; - uint8_t correction_span; - uint8_t head_offset_count; - uint8_t data_strobe_offset_count; - uint8_t flags2; - uint8_t write_retry_count; - uint8_t flags3; - be16_t recovery_time_limit; + uint8_t page_code; + uint8_t page_length; + #define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A + uint8_t flags1; + #define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7) + #define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6) + #define SBC_MP_RW_ERR_RECOV_TB (1 << 5) + #define SBC_MP_RW_ERR_RECOV_RC (1 << 4) + #define SBC_MP_RW_ERR_RECOV_ERR (1 << 3) + #define SBC_MP_RW_ERR_RECOV_PER (1 << 2) + #define SBC_MP_RW_ERR_RECOV_DTE (1 << 1) + #define SBC_MP_RW_ERR_RECOV_DCR (1 << 0) + uint8_t read_retry_count; + uint8_t correction_span; + uint8_t head_offset_count; + uint8_t data_strobe_offset_count; + uint8_t flags2; + uint8_t write_retry_count; + uint8_t flags3; + be16_t recovery_time_limit; }; //@} @@ -164,8 +162,8 @@ struct sbc_rdwr_error_recovery_mode_page { * \brief SBC-2 READ CAPACITY (10) parameter data */ struct sbc_read_capacity10_data { - be32_t max_lba; //!< LBA of last logical block - be32_t block_len; //!< Number of bytes in the last logical block + be32_t max_lba; //!< LBA of last logical block + be32_t block_len; //!< Number of bytes in the last logical block }; //@} diff --git a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp index 34cc256b30..74cfd9b39b 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp @@ -6,7 +6,7 @@ #include "../../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../../sd/cardreader.h" extern "C" { @@ -18,30 +18,29 @@ extern "C" { void sd_mmc_spi_mem_init() { } -Ctrl_status sd_mmc_spi_test_unit_ready() { - #ifdef DISABLE_DUE_SD_MMC - return CTRL_NO_PRESENT; - #endif - if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted()) - return CTRL_NO_PRESENT; - return CTRL_GOOD; -} - -// NOTE: This function is defined as returning the address of the last block -// in the card, which is cardSize() - 1 -Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector) { - if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted()) - return CTRL_NO_PRESENT; - *nb_sector = card.diskIODriver()->cardSize() - 1; - return CTRL_GOOD; +inline bool media_ready() { + return card.isMounted() && card.isInserted() && !card.isFileOpen() && !card.isStillPrinting(); } bool sd_mmc_spi_unload(bool) { return true; } bool sd_mmc_spi_wr_protect() { return false; } -bool sd_mmc_spi_removal() { - return (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted()); +bool sd_mmc_spi_removal() { return !media_ready(); } + +Ctrl_status sd_mmc_spi_test_unit_ready() { + #if ENABLED(DISABLE_DUE_SD_MMC) + return CTRL_NO_PRESENT; + #endif + return sd_mmc_spi_removal() ? CTRL_NO_PRESENT : CTRL_GOOD; +} + +// NOTE: This function is defined as returning the address of the last block +// in the card, which is cardSize() - 1 +Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector) { + if (sd_mmc_spi_removal()) return CTRL_NO_PRESENT; + *nb_sector = card.diskIODriver()->cardSize() - 1; + return CTRL_GOOD; } #if ACCESS_USB == true @@ -58,11 +57,11 @@ uint8_t sector_buf[SD_MMC_BLOCK_SIZE]; // #define DEBUG_MMC Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector) { - #ifdef DISABLE_DUE_SD_MMC + #if ENABLED(DISABLE_DUE_SD_MMC) return CTRL_NO_PRESENT; #endif - if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted()) - return CTRL_NO_PRESENT; + + if (sd_mmc_spi_removal()) return CTRL_NO_PRESENT; #ifdef DEBUG_MMC { @@ -98,11 +97,11 @@ Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector) { } Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector) { - #ifdef DISABLE_DUE_SD_MMC + #if ENABLED(DISABLE_DUE_SD_MMC) return CTRL_NO_PRESENT; #endif - if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted()) - return CTRL_NO_PRESENT; + + if (sd_mmc_spi_removal()) return CTRL_NO_PRESENT; #ifdef DEBUG_MMC { @@ -138,5 +137,5 @@ Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector) { #endif // ACCESS_USB == true -#endif // SDSUPPORT +#endif // HAS_MEDIA #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h index 553fd3c29a..464d106e52 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h @@ -45,7 +45,6 @@ * Support and FAQ: visit Atmel Support */ - #ifndef _SD_MMC_SPI_MEM_H_ #define _SD_MMC_SPI_MEM_H_ @@ -63,22 +62,19 @@ #error sd_mmc_spi_mem.h is #included although SD_MMC_SPI_MEM is disabled #endif - #include "ctrl_access.h" - //_____ D E F I N I T I O N S ______________________________________________ #define SD_MMC_REMOVED 0 #define SD_MMC_INSERTED 1 #define SD_MMC_REMOVING 2 - //---- CONTROL FUNCTIONS ---- //! //! @brief This function initializes the hw/sw resources required to drive the SD_MMC_SPI. //!/ -extern void sd_mmc_spi_mem_init(void); +void sd_mmc_spi_mem_init(); //! //! @brief This function tests the state of the SD_MMC memory and sends it to the Host. @@ -91,7 +87,7 @@ extern void sd_mmc_spi_mem_init(void); //! Media not present -> CTRL_NO_PRESENT //! Media has changed -> CTRL_BUSY //!/ -extern Ctrl_status sd_mmc_spi_test_unit_ready(void); +Ctrl_status sd_mmc_spi_test_unit_ready(); //! //! @brief This function gives the address of the last valid sector. @@ -102,7 +98,7 @@ extern Ctrl_status sd_mmc_spi_test_unit_ready(void); //! Media ready -> CTRL_GOOD //! Media not present -> CTRL_NO_PRESENT //!/ -extern Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector); +Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector); /*! \brief Unload/Load the SD/MMC card selected * @@ -113,7 +109,7 @@ extern Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector); * * \return \c true if unload/load done success. */ -extern bool sd_mmc_spi_unload(bool unload); +bool sd_mmc_spi_unload(bool unload); //! //! @brief This function returns the write protected status of the memory. @@ -124,15 +120,14 @@ extern bool sd_mmc_spi_unload(bool unload); //! //! @return false -> the memory is not write-protected (always) //!/ -extern bool sd_mmc_spi_wr_protect(void); +bool sd_mmc_spi_wr_protect(); //! //! @brief This function tells if the memory has been removed or not. //! //! @return false -> The memory isn't removed //! -extern bool sd_mmc_spi_removal(void); - +bool sd_mmc_spi_removal(); //---- ACCESS DATA FUNCTIONS ---- @@ -152,7 +147,7 @@ extern bool sd_mmc_spi_removal(void); //! It is ready -> CTRL_GOOD //! A error occur -> CTRL_FAIL //! -extern Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector); +Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector); //! This function initializes the SD/MMC memory for a write operation //! @@ -166,7 +161,7 @@ extern Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector); //! It is ready -> CTRL_GOOD //! An error occurs -> CTRL_FAIL //! -extern Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector); +Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector); #endif // #if ACCESS_USB == true diff --git a/Marlin/src/HAL/DUE/usb/spc_protocol.h b/Marlin/src/HAL/DUE/usb/spc_protocol.h index d67cc5c788..808c388f4f 100644 --- a/Marlin/src/HAL/DUE/usb/spc_protocol.h +++ b/Marlin/src/HAL/DUE/usb/spc_protocol.h @@ -59,23 +59,23 @@ //! \name SCSI commands defined by SPC-2 //@{ -#define SPC_TEST_UNIT_READY 0x00 -#define SPC_REQUEST_SENSE 0x03 -#define SPC_INQUIRY 0x12 -#define SPC_MODE_SELECT6 0x15 -#define SPC_MODE_SENSE6 0x1A -#define SPC_SEND_DIAGNOSTIC 0x1D -#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E -#define SPC_MODE_SENSE10 0x5A -#define SPC_REPORT_LUNS 0xA0 +#define SPC_TEST_UNIT_READY 0x00 +#define SPC_REQUEST_SENSE 0x03 +#define SPC_INQUIRY 0x12 +#define SPC_MODE_SELECT6 0x15 +#define SPC_MODE_SENSE6 0x1A +#define SPC_SEND_DIAGNOSTIC 0x1D +#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E +#define SPC_MODE_SENSE10 0x5A +#define SPC_REPORT_LUNS 0xA0 //@} //! \brief May be set in byte 0 of the INQUIRY CDB //@{ //! Enable Vital Product Data -#define SCSI_INQ_REQ_EVPD 0x01 +#define SCSI_INQ_REQ_EVPD 0x01 //! Command Support Data specified by the PAGE OR OPERATION CODE field -#define SCSI_INQ_REQ_CMDT 0x02 +#define SCSI_INQ_REQ_CMDT 0x02 //@} COMPILER_PACK_SET(1) @@ -84,110 +84,110 @@ COMPILER_PACK_SET(1) * \brief SCSI Standard Inquiry data structure */ struct scsi_inquiry_data { - uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type -#define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected -#define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected -#define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported -#define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC) -#define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access -#define SCSI_INQ_DT_PRINTER 0x02 //!< Printer -#define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device -#define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device -#define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device -#define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory -#define SCSI_INQ_DT_MC 0x08 //!< Medium Changer -#define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller -#define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services -#define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access -#define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer -#define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands -#define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage -#define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral - uint8_t flags1; //!< Flags (byte 1) -#define SCSI_INQ_RMB 0x80 //!< Removable Medium - uint8_t version; //!< Version -#define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance -#define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC) -#define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2) -#define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2) -#define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3) - uint8_t flags3; //!< Flags (byte 3) -#define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported -#define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing -#define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format - uint8_t addl_len; //!< Additional Length (n-4) -#define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot - uint8_t flags5; //!< Flags (byte 5) -#define SCSI_INQ_SCCS 0x80 - uint8_t flags6; //!< Flags (byte 6) -#define SCSI_INQ_BQUE 0x80 -#define SCSI_INQ_ENCSERV 0x40 -#define SCSI_INQ_MULTIP 0x10 -#define SCSI_INQ_MCHGR 0x08 -#define SCSI_INQ_ADDR16 0x01 - uint8_t flags7; //!< Flags (byte 7) -#define SCSI_INQ_WBUS16 0x20 -#define SCSI_INQ_SYNC 0x10 -#define SCSI_INQ_LINKED 0x08 -#define SCSI_INQ_CMDQUE 0x02 - uint8_t vendor_id[8]; //!< T10 Vendor Identification - uint8_t product_id[16]; //!< Product Identification - uint8_t product_rev[4]; //!< Product Revision Level + uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type + #define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected + #define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected + #define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported + #define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC) + #define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access + #define SCSI_INQ_DT_PRINTER 0x02 //!< Printer + #define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device + #define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device + #define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device + #define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory + #define SCSI_INQ_DT_MC 0x08 //!< Medium Changer + #define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller + #define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services + #define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access + #define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer + #define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands + #define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage + #define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral + uint8_t flags1; //!< Flags (byte 1) + #define SCSI_INQ_RMB 0x80 //!< Removable Medium + uint8_t version; //!< Version + #define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance + #define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC) + #define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2) + #define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2) + #define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3) + uint8_t flags3; //!< Flags (byte 3) + #define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported + #define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing + #define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format + uint8_t addl_len; //!< Additional Length (n-4) + #define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot + uint8_t flags5; //!< Flags (byte 5) + #define SCSI_INQ_SCCS 0x80 + uint8_t flags6; //!< Flags (byte 6) + #define SCSI_INQ_BQUE 0x80 + #define SCSI_INQ_ENCSERV 0x40 + #define SCSI_INQ_MULTIP 0x10 + #define SCSI_INQ_MCHGR 0x08 + #define SCSI_INQ_ADDR16 0x01 + uint8_t flags7; //!< Flags (byte 7) + #define SCSI_INQ_WBUS16 0x20 + #define SCSI_INQ_SYNC 0x10 + #define SCSI_INQ_LINKED 0x08 + #define SCSI_INQ_CMDQUE 0x02 + uint8_t vendor_id[8]; //!< T10 Vendor Identification + uint8_t product_id[16]; //!< Product Identification + uint8_t product_rev[4]; //!< Product Revision Level }; /** * \brief SCSI Standard Request sense data structure */ struct scsi_request_sense_data { - /* 1st byte: REQUEST SENSE response flags*/ - uint8_t valid_reponse_code; -#define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information -#define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F -#define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors) -#define SCSI_SENSE_DEFERRED 0x71 + /* 1st byte: REQUEST SENSE response flags*/ + uint8_t valid_reponse_code; + #define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information + #define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F + #define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors) + #define SCSI_SENSE_DEFERRED 0x71 - /* 2nd byte */ - uint8_t obsolete; + /* 2nd byte */ + uint8_t obsolete; - /* 3rd byte */ - uint8_t sense_flag_key; -#define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark. -#define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists. -#define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium. -#define SCSI_SENSE_RESERVED 0x10 //!< Reserved -#define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key + /* 3rd byte */ + uint8_t sense_flag_key; + #define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark. + #define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists. + #define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium. + #define SCSI_SENSE_RESERVED 0x10 //!< Reserved + #define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key - /* 4th to 7th bytes - INFORMATION field */ - uint8_t information[4]; + /* 4th to 7th bytes - INFORMATION field */ + uint8_t information[4]; - /* 8th byte - ADDITIONAL SENSE LENGTH field */ - uint8_t AddSenseLen; -#define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8) + /* 8th byte - ADDITIONAL SENSE LENGTH field */ + uint8_t AddSenseLen; + #define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8) - /* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */ - uint8_t CmdSpecINFO[4]; + /* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */ + uint8_t CmdSpecINFO[4]; - /* 13th byte - ADDITIONAL SENSE CODE field */ - uint8_t AddSenseCode; + /* 13th byte - ADDITIONAL SENSE CODE field */ + uint8_t AddSenseCode; - /* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */ - uint8_t AddSnsCodeQlfr; + /* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */ + uint8_t AddSnsCodeQlfr; - /* 15th byte - FIELD REPLACEABLE UNIT CODE field */ - uint8_t FldReplUnitCode; + /* 15th byte - FIELD REPLACEABLE UNIT CODE field */ + uint8_t FldReplUnitCode; - /* 16th byte */ - uint8_t SenseKeySpec[3]; -#define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information + /* 16th byte */ + uint8_t SenseKeySpec[3]; + #define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information }; COMPILER_PACK_RESET() /* Vital Product Data page codes */ enum scsi_vpd_page_code { - SCSI_VPD_SUPPORTED_PAGES = 0x00, - SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80, - SCSI_VPD_DEVICE_IDENTIFICATION = 0x83, + SCSI_VPD_SUPPORTED_PAGES = 0x00, + SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80, + SCSI_VPD_DEVICE_IDENTIFICATION = 0x83, }; #define SCSI_VPD_HEADER_SIZE 4 @@ -200,37 +200,36 @@ enum scsi_vpd_page_code { #define SCSI_VPD_ID_TYPE_T10 1 - /* Sense keys */ enum scsi_sense_key { - SCSI_SK_NO_SENSE = 0x0, - SCSI_SK_RECOVERED_ERROR = 0x1, - SCSI_SK_NOT_READY = 0x2, - SCSI_SK_MEDIUM_ERROR = 0x3, - SCSI_SK_HARDWARE_ERROR = 0x4, - SCSI_SK_ILLEGAL_REQUEST = 0x5, - SCSI_SK_UNIT_ATTENTION = 0x6, - SCSI_SK_DATA_PROTECT = 0x7, - SCSI_SK_BLANK_CHECK = 0x8, - SCSI_SK_VENDOR_SPECIFIC = 0x9, - SCSI_SK_COPY_ABORTED = 0xA, - SCSI_SK_ABORTED_COMMAND = 0xB, - SCSI_SK_VOLUME_OVERFLOW = 0xD, - SCSI_SK_MISCOMPARE = 0xE, + SCSI_SK_NO_SENSE = 0x0, + SCSI_SK_RECOVERED_ERROR = 0x1, + SCSI_SK_NOT_READY = 0x2, + SCSI_SK_MEDIUM_ERROR = 0x3, + SCSI_SK_HARDWARE_ERROR = 0x4, + SCSI_SK_ILLEGAL_REQUEST = 0x5, + SCSI_SK_UNIT_ATTENTION = 0x6, + SCSI_SK_DATA_PROTECT = 0x7, + SCSI_SK_BLANK_CHECK = 0x8, + SCSI_SK_VENDOR_SPECIFIC = 0x9, + SCSI_SK_COPY_ABORTED = 0xA, + SCSI_SK_ABORTED_COMMAND = 0xB, + SCSI_SK_VOLUME_OVERFLOW = 0xD, + SCSI_SK_MISCOMPARE = 0xE, }; /* Additional Sense Code / Additional Sense Code Qualifier pairs */ enum scsi_asc_ascq { - SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000, - SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405, - SCSI_ASC_WRITE_ERROR = 0x0C00, - SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100, - SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000, - SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400, - SCSI_ASC_WRITE_PROTECTED = 0x2700, - SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800, - SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00, - SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400, + SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000, + SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405, + SCSI_ASC_WRITE_ERROR = 0x0C00, + SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100, + SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000, + SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400, + SCSI_ASC_WRITE_PROTECTED = 0x2700, + SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800, + SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00, + SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400, }; /** @@ -240,9 +239,9 @@ enum scsi_asc_ascq { * that are applicable to all SCSI devices. */ enum scsi_spc_mode { - SCSI_MS_MODE_VENDOR_SPEC = 0x00, - SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page - SCSI_MS_MODE_ALL = 0x3F, + SCSI_MS_MODE_VENDOR_SPEC = 0x00, + SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page + SCSI_MS_MODE_ALL = 0x3F, }; /** @@ -250,51 +249,45 @@ enum scsi_spc_mode { * See chapter 8.3.8 */ struct spc_control_page_info_execpt { - uint8_t page_code; - uint8_t page_length; -#define SPC_MP_INFEXP_PAGE_LENGTH 0x0A - uint8_t flags1; -#define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control -#define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted -#define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity -#define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable -#define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable -#define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit - uint8_t mrie; -#define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00 -#define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01 -#define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02 -#define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03 -#define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04 -#define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05 -#define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06 - be32_t interval_timer; - be32_t report_count; + uint8_t page_code; + uint8_t page_length; + #define SPC_MP_INFEXP_PAGE_LENGTH 0x0A + uint8_t flags1; + #define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control + #define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted + #define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity + #define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable + #define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable + #define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit + uint8_t mrie; + #define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00 + #define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01 + #define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02 + #define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03 + #define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04 + #define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05 + #define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06 + be32_t interval_timer; + be32_t report_count; }; - enum scsi_spc_mode_sense_pc { - SCSI_MS_SENSE_PC_CURRENT = 0, - SCSI_MS_SENSE_PC_CHANGEABLE = 1, - SCSI_MS_SENSE_PC_DEFAULT = 2, - SCSI_MS_SENSE_PC_SAVED = 3, + SCSI_MS_SENSE_PC_CURRENT = 0, + SCSI_MS_SENSE_PC_CHANGEABLE = 1, + SCSI_MS_SENSE_PC_DEFAULT = 2, + SCSI_MS_SENSE_PC_SAVED = 3, }; - - -static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb) -{ - return (cdb[1] >> 3) & 1; +static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb) { + return (cdb[1] >> 3) & 1; } -static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb) -{ - return cdb[2] & 0x3F; +static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb) { + return cdb[2] & 0x3F; } -static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) -{ - return cdb[2] >> 6; +static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) { + return cdb[2] >> 6; } /** @@ -302,10 +295,10 @@ static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) * SENSE(6) */ struct scsi_mode_param_header6 { - uint8_t mode_data_length; //!< Number of bytes after this - uint8_t medium_type; //!< Medium Type - uint8_t device_specific_parameter; //!< Defined by command set - uint8_t block_descriptor_length; //!< Length of block descriptors + uint8_t mode_data_length; //!< Number of bytes after this + uint8_t medium_type; //!< Medium Type + uint8_t device_specific_parameter; //!< Defined by command set + uint8_t block_descriptor_length; //!< Length of block descriptors }; /** @@ -313,23 +306,23 @@ struct scsi_mode_param_header6 { * SENSE(10) */ struct scsi_mode_param_header10 { - be16_t mode_data_length; //!< Number of bytes after this - uint8_t medium_type; //!< Medium Type - uint8_t device_specific_parameter; //!< Defined by command set - uint8_t flags4; //!< LONGLBA in bit 0 - uint8_t reserved; - be16_t block_descriptor_length; //!< Length of block descriptors + be16_t mode_data_length; //!< Number of bytes after this + uint8_t medium_type; //!< Medium Type + uint8_t device_specific_parameter; //!< Defined by command set + uint8_t flags4; //!< LONGLBA in bit 0 + uint8_t reserved; + be16_t block_descriptor_length; //!< Length of block descriptors }; /** * \brief SCSI Page_0 Mode Page header (SPF not set) */ struct scsi_mode_page_0_header { - uint8_t page_code; -#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable -#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format - uint8_t page_length; //!< Number of bytes after this -#define SCSI_MS_PAGE_LEN(total) ((total) - 2) + uint8_t page_code; +#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable +#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format + uint8_t page_length; //!< Number of bytes after this +#define SCSI_MS_PAGE_LEN(total) ((total) - 2) }; //@} diff --git a/Marlin/src/HAL/DUE/usb/sysclk.h b/Marlin/src/HAL/DUE/usb/sysclk.h index 16db8c86d3..4001366868 100644 --- a/Marlin/src/HAL/DUE/usb/sysclk.h +++ b/Marlin/src/HAL/DUE/usb/sysclk.h @@ -71,7 +71,7 @@ * \subsection sysclk_quickstart_use_case_1_setup_steps Initialization code * Add to the application initialization code: * \code - sysclk_init(); + sysclk_init(); \endcode * * \subsection sysclk_quickstart_use_case_1_setup_steps_workflow Workflow @@ -82,15 +82,15 @@ * Add or uncomment the following in your conf_clock.h header file, commenting out all other * definitions of the same symbol(s): * \code - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK - // Fpll0 = (Fclk * PLL_mul) / PLL_div - #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL - #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) - #define CONFIG_PLL0_DIV 1 + // Fpll0 = (Fclk * PLL_mul) / PLL_div + #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL + #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) + #define CONFIG_PLL0_DIV 1 - // Fbus = Fsys / BUS_div - #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 + // Fbus = Fsys / BUS_div + #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 \endcode * * \subsection sysclk_quickstart_use_case_1_example_workflow Workflow @@ -100,14 +100,14 @@ * \code #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL \endcode * -# Configure the PLL module to multiply the external fast crystal oscillator frequency up to 84MHz: * \code - #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) - #define CONFIG_PLL0_DIV 1 + #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) + #define CONFIG_PLL0_DIV 1 \endcode * \note For user boards, \c BOARD_FREQ_MAINCK_XTAL should be defined in the board \c conf_board.h configuration * file as the frequency of the fast crystal attached to the microcontroller. * -# Configure the main clock to run at the full 84MHz, disable scaling of the main system clock speed: * \code - #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 + #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 \endcode * \note Some dividers are powers of two, while others are integer division factors. Refer to the * formulas in the conf_clock.h template commented above each division define. @@ -136,7 +136,7 @@ extern "C" { * initialization. */ #ifndef CONFIG_SYSCLK_SOURCE -# define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC #endif /** * \def CONFIG_SYSCLK_PRES @@ -149,7 +149,7 @@ extern "C" { * after initialization. */ #ifndef CONFIG_SYSCLK_PRES -# define CONFIG_SYSCLK_PRES 0 + #define CONFIG_SYSCLK_PRES 0 #endif //@} @@ -197,7 +197,7 @@ extern "C" { * USB is not required. */ #ifdef __DOXYGEN__ -# define CONFIG_USBCLK_SOURCE + #define CONFIG_USBCLK_SOURCE #endif /** @@ -209,10 +209,9 @@ extern "C" { * defined. */ #ifdef __DOXYGEN__ -# define CONFIG_USBCLK_DIV + #define CONFIG_USBCLK_DIV #endif - extern void sysclk_enable_usb(void); extern void sysclk_disable_usb(void); diff --git a/Marlin/src/HAL/DUE/usb/udc.c b/Marlin/src/HAL/DUE/usb/udc.c index 60bf0cfff3..f6a4243d1d 100644 --- a/Marlin/src/HAL/DUE/usb/udc.c +++ b/Marlin/src/HAL/DUE/usb/udc.c @@ -83,7 +83,6 @@ static usb_iface_desc_t UDC_DESC_STORAGE *udc_ptr_iface; //! @} - //! \name Internal structure to store the USB device main strings //! @{ diff --git a/Marlin/src/HAL/DUE/usb/udc.h b/Marlin/src/HAL/DUE/usb/udc.h index 8d92eb5c03..e8c0e7fbea 100644 --- a/Marlin/src/HAL/DUE/usb/udc.h +++ b/Marlin/src/HAL/DUE/usb/udc.h @@ -144,15 +144,15 @@ extern "C" { * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: * \code - // Authorize VBUS monitoring - if (!udc_include_vbus_monitoring()) { - // Implement custom VBUS monitoring via GPIO or other - } - Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other - { - // Attach USB Device - udc_attach(); - } + // Authorize VBUS monitoring + if (!udc_include_vbus_monitoring()) { + // Implement custom VBUS monitoring via GPIO or other + } + Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other + { + // Attach USB Device + udc_attach(); + } \endcode * * - Case of battery charging. conf_usb.h file contains define @@ -160,21 +160,20 @@ extern "C" { * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: * \code - Event VBUS present() // VBUS interrupt or GPIO interrupt or .. - { - // Authorize battery charging, but wait key press to start USB. - } - Event Key press() - { - // Stop batteries charging - // Start USB - udc_attach(); - } + Event VBUS present() // VBUS interrupt or GPIO interrupt or .. + { + // Authorize battery charging, but wait key press to start USB. + } + Event Key press() + { + // Stop batteries charging + // Start USB + udc_attach(); + } \endcode */ -static inline bool udc_include_vbus_monitoring(void) -{ - return udd_include_vbus_monitoring(); +static inline bool udc_include_vbus_monitoring(void) { + return udd_include_vbus_monitoring(); } /*! \brief Start the USB Device stack @@ -192,32 +191,26 @@ void udc_stop(void); * then it will attach device when an acceptable Vbus * level from the host is detected. */ -static inline void udc_attach(void) -{ - udd_attach(); +static inline void udc_attach(void) { + udd_attach(); } - /** * \brief Detaches the device from the bus * * The driver must remove pull-up on USB line D- or D+. */ -static inline void udc_detach(void) -{ - udd_detach(); +static inline void udc_detach(void) { + udd_detach(); } - /*! \brief The USB driver sends a resume signal called \e "Upstream Resume" * This is authorized only when the remote wakeup feature is enabled by host. */ -static inline void udc_remotewakeup(void) -{ - udd_send_remotewakeup(); +static inline void udc_remotewakeup(void) { + udd_send_remotewakeup(); } - /** * \brief Returns a pointer on the current interface descriptor * @@ -236,7 +229,7 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * - USB Device Controller (UDC) provides USB chapter 9 compliance * - USB Device Interface (UDI) provides USB Class compliance * - USB Device Driver (UDD) provides USB Driver for each Atmel MCU - + * * Many USB Device applications can be implemented on Atmel MCU. * Atmel provides many application notes for different applications: * - AVR4900, provides general information about Device Stack @@ -296,23 +289,23 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * for AVR and SAM3/4 devices, add to the initialization code: * \code - sysclk_init(); - irq_initialize_vectors(); - cpu_irq_enable(); - board_init(); - sleepmgr_init(); // Optional + sysclk_init(); + irq_initialize_vectors(); + cpu_irq_enable(); + board_init(); + sleepmgr_init(); // Optional \endcode * * For SAMD devices, add to the initialization code: * \code - system_init(); - irq_initialize_vectors(); - cpu_irq_enable(); - sleepmgr_init(); // Optional + system_init(); + irq_initialize_vectors(); + cpu_irq_enable(); + sleepmgr_init(); // Optional \endcode * Add to the main IDLE loop: * \code - sleepmgr_enter_sleep(); // Optional + sleepmgr_enter_sleep(); // Optional \endcode * */ @@ -324,20 +317,20 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * Content of conf_usb.h: * \code - #define USB_DEVICE_VENDOR_ID 0x03EB - #define USB_DEVICE_PRODUCT_ID 0xXXXX - #define USB_DEVICE_MAJOR_VERSION 1 - #define USB_DEVICE_MINOR_VERSION 0 - #define USB_DEVICE_POWER 100 - #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED + #define USB_DEVICE_VENDOR_ID 0x03EB + #define USB_DEVICE_PRODUCT_ID 0xXXXX + #define USB_DEVICE_MAJOR_VERSION 1 + #define USB_DEVICE_MINOR_VERSION 0 + #define USB_DEVICE_POWER 100 + #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED \endcode * * Add to application C-file: * \code - void usb_init(void) - { - udc_start(); - } + void usb_init(void) + { + udc_start(); + } \endcode */ @@ -349,17 +342,17 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * -# Ensure that conf_usb.h is available and contains the following configuration * which is the main USB device configuration: * - \code // Vendor ID provided by USB org (ATMEL 0x03EB) - #define USB_DEVICE_VENDOR_ID 0x03EB // Type Word - // Product ID (Atmel PID referenced in usb_atmel.h) - #define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word - // Major version of the device - #define USB_DEVICE_MAJOR_VERSION 1 // Type Byte - // Minor version of the device - #define USB_DEVICE_MINOR_VERSION 0 // Type Byte - // Maximum device power (mA) - #define USB_DEVICE_POWER 100 // Type 9-bits - // USB attributes to enable features - #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode + #define USB_DEVICE_VENDOR_ID 0x03EB // Type Word + // Product ID (Atmel PID referenced in usb_atmel.h) + #define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word + // Major version of the device + #define USB_DEVICE_MAJOR_VERSION 1 // Type Byte + // Minor version of the device + #define USB_DEVICE_MINOR_VERSION 0 // Type Byte + // Maximum device power (mA) + #define USB_DEVICE_POWER 100 // Type 9-bits + // USB attributes to enable features + #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode * -# Call the USB device stack start function to enable stack and start USB: * - \code udc_start(); \endcode * \note In case of USB dual roles (Device and Host) managed through USB OTG connector @@ -372,90 +365,90 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * Content of XMEGA conf_clock.h: * \code - // Configuration based on internal RC: - // USB clock need of 48Mhz - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC - #define CONFIG_OSC_RC32_CAL 48000000UL - #define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF - // CPU clock need of clock > 12MHz to run with USB (Here 24MHz) - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ - #define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2 - #define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1 + // Configuration based on internal RC: + // USB clock need of 48Mhz + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC + #define CONFIG_OSC_RC32_CAL 48000000UL + #define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF + // CPU clock need of clock > 12MHz to run with USB (Here 24MHz) + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ + #define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2 + #define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1 \endcode * * Content of conf_clock.h for AT32UC3A0, AT32UC3A1, AT32UC3B devices (USBB): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 - #define CONFIG_PLL1_MUL 8 - #define CONFIG_PLL1_DIV 2 - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // Configuration based on 12MHz external OSC: + #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 + #define CONFIG_PLL1_MUL 8 + #define CONFIG_PLL1_DIV 2 + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) \endcode * * Content of conf_clock.h for AT32UC3A3, AT32UC3A4 devices (USBB with high speed support): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // Configuration based on 12MHz external OSC: + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) \endcode * * Content of conf_clock.h for AT32UC3C, ATUCXXD, ATUCXXL3U, ATUCXXL4U devices (USBC): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 - #define CONFIG_PLL1_MUL 8 - #define CONFIG_PLL1_DIV 2 - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) - // CPU clock need of clock > 25MHz to run with USBC - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1 + // Configuration based on 12MHz external OSC: + #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 + #define CONFIG_PLL1_MUL 8 + #define CONFIG_PLL1_DIV 2 + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // CPU clock need of clock > 25MHz to run with USBC + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1 \endcode * * Content of conf_clock.h for SAM3S, SAM3SD, SAM4S devices (UPD: USB Peripheral Device): * \code - // PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div) - #define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL - #define CONFIG_PLL1_MUL 16 - #define CONFIG_PLL1_DIV 2 - // USB Clock Source Options (Fusb = FpllX / USB_div) - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 2 + // PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div) + #define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL + #define CONFIG_PLL1_MUL 16 + #define CONFIG_PLL1_DIV 2 + // USB Clock Source Options (Fusb = FpllX / USB_div) + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 2 \endcode * * Content of conf_clock.h for SAM3U device (UPDHS: USB Peripheral Device High Speed): * \code - // USB Clock Source fixed at UPLL. + // USB Clock Source fixed at UPLL. \endcode * * Content of conf_clock.h for SAM3X, SAM3A devices (UOTGHS: USB OTG High Speed): * \code - // USB Clock Source fixed at UPLL. - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL - #define CONFIG_USBCLK_DIV 1 + // USB Clock Source fixed at UPLL. + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL + #define CONFIG_USBCLK_DIV 1 \endcode * * Content of conf_clocks.h for SAMD devices (USB): * \code - // System clock bus configuration - # define CONF_CLOCK_FLASH_WAIT_STATES 2 + // System clock bus configuration + # define CONF_CLOCK_FLASH_WAIT_STATES 2 - // USB Clock Source fixed at DFLL. - // SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop - # define CONF_CLOCK_DFLL_ENABLE true - # define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY - # define CONF_CLOCK_DFLL_ON_DEMAND true + // USB Clock Source fixed at DFLL. + // SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop + # define CONF_CLOCK_DFLL_ENABLE true + # define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY + # define CONF_CLOCK_DFLL_ON_DEMAND true - // Set this to true to configure the GCLK when running clocks_init. - // If set to false, none of the GCLK generators will be configured in clocks_init(). - # define CONF_CLOCK_CONFIGURE_GCLK true + // Set this to true to configure the GCLK when running clocks_init. + // If set to false, none of the GCLK generators will be configured in clocks_init(). + # define CONF_CLOCK_CONFIGURE_GCLK true - // Configure GCLK generator 0 (Main Clock) - # define CONF_CLOCK_GCLK_0_ENABLE true - # define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true - # define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL - # define CONF_CLOCK_GCLK_0_PRESCALER 1 - # define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false + // Configure GCLK generator 0 (Main Clock) + # define CONF_CLOCK_GCLK_0_ENABLE true + # define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true + # define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL + # define CONF_CLOCK_GCLK_0_PRESCALER 1 + # define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false \endcode */ @@ -474,34 +467,34 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_1_usage_code Example code * Content of conf_usb.h: * \code - #if // Low speed - #define USB_DEVICE_LOW_SPEED - // #define USB_DEVICE_HS_SUPPORT + #if // Low speed + #define USB_DEVICE_LOW_SPEED + // #define USB_DEVICE_HS_SUPPORT - #elif // Full speed - // #define USB_DEVICE_LOW_SPEED - // #define USB_DEVICE_HS_SUPPORT + #elif // Full speed + // #define USB_DEVICE_LOW_SPEED + // #define USB_DEVICE_HS_SUPPORT - #elif // High speed - // #define USB_DEVICE_LOW_SPEED - #define USB_DEVICE_HS_SUPPORT + #elif // High speed + // #define USB_DEVICE_LOW_SPEED + #define USB_DEVICE_HS_SUPPORT - #endif + #endif \endcode * * \subsection udc_use_case_1_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB device low speed (1.5Mbit/s): * - \code #define USB_DEVICE_LOW_SPEED - //#define USB_DEVICE_HS_SUPPORT \endcode + //#define USB_DEVICE_HS_SUPPORT \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB device full speed (12Mbit/s): * - \code //#define USB_DEVICE_LOW_SPEED - //#define USB_DEVICE_HS_SUPPORT \endcode + //#define USB_DEVICE_HS_SUPPORT \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB device high speed (480Mbit/s): * - \code //#define USB_DEVICE_LOW_SPEED - #define USB_DEVICE_HS_SUPPORT \endcode + #define USB_DEVICE_HS_SUPPORT \endcode */ /** @@ -518,20 +511,20 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_2_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" - #define USB_DEVICE_PRODUCT_NAME "Product name" - #define USB_DEVICE_SERIAL_NAME "12...EF" + #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" + #define USB_DEVICE_PRODUCT_NAME "Product name" + #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode * * \subsection udc_use_case_2_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable different USB strings: * - \code // Static ASCII name for the manufacture - #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode + #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode * - \code // Static ASCII name for the product - #define USB_DEVICE_PRODUCT_NAME "Product name" \endcode + #define USB_DEVICE_PRODUCT_NAME "Product name" \endcode * - \code // Static ASCII name to enable and set a serial number - #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode + #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode */ /** @@ -548,42 +541,42 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_3_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_ATTR \ - (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) - #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() - extern void my_callback_remotewakeup_enable(void); - #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() - extern void my_callback_remotewakeup_disable(void); + #define USB_DEVICE_ATTR \ + (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) + #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() + extern void my_callback_remotewakeup_enable(void); + #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() + extern void my_callback_remotewakeup_disable(void); \endcode * * Add to application C-file: * \code - void my_callback_remotewakeup_enable(void) - { - // Enable application wakeup events (e.g. enable GPIO interrupt) - } - void my_callback_remotewakeup_disable(void) - { - // Disable application wakeup events (e.g. disable GPIO interrupt) - } + void my_callback_remotewakeup_enable(void) + { + // Enable application wakeup events (e.g. enable GPIO interrupt) + } + void my_callback_remotewakeup_disable(void) + { + // Disable application wakeup events (e.g. disable GPIO interrupt) + } - void my_interrupt_event(void) - { - udc_remotewakeup(); - } + void my_interrupt_event(void) + { + udc_remotewakeup(); + } \endcode * * \subsection udc_use_case_3_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable remote wakeup feature: * - \code // Authorizes the remote wakeup feature - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode * - \code // Define callback called when the host enables the remotewakeup feature - #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() - extern void my_callback_remotewakeup_enable(void); \endcode + #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() + extern void my_callback_remotewakeup_enable(void); \endcode * - \code // Define callback called when the host disables the remotewakeup feature - #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() - extern void my_callback_remotewakeup_disable(void); \endcode + #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() + extern void my_callback_remotewakeup_disable(void); \endcode * -# Send a remote wakeup (USB upstream): * - \code udc_remotewakeup(); \endcode */ @@ -603,40 +596,40 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_5_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) - #define UDC_SUSPEND_EVENT() user_callback_suspend_action() - extern void user_callback_suspend_action(void) - #define UDC_RESUME_EVENT() user_callback_resume_action() - extern void user_callback_resume_action(void) + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) + #define UDC_SUSPEND_EVENT() user_callback_suspend_action() + extern void user_callback_suspend_action(void) + #define UDC_RESUME_EVENT() user_callback_resume_action() + extern void user_callback_resume_action(void) \endcode * * Add to application C-file: * \code - void user_callback_suspend_action(void) - { - // Disable hardware component to reduce power consumption - } - void user_callback_resume_action(void) - { - // Re-enable hardware component - } + void user_callback_suspend_action(void) + { + // Disable hardware component to reduce power consumption + } + void user_callback_resume_action(void) + { + // Re-enable hardware component + } \endcode * * \subsection udc_use_case_5_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters: * - \code // Authorizes the BUS power feature - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode * - \code // Define callback called when the host suspend the USB line - #define UDC_SUSPEND_EVENT() user_callback_suspend_action() - extern void user_callback_suspend_action(void); \endcode + #define UDC_SUSPEND_EVENT() user_callback_suspend_action() + extern void user_callback_suspend_action(void); \endcode * - \code // Define callback called when the host or device resume the USB line - #define UDC_RESUME_EVENT() user_callback_resume_action() - extern void user_callback_resume_action(void); \endcode + #define UDC_RESUME_EVENT() user_callback_resume_action() + extern void user_callback_resume_action(void); \endcode * -# Reduce power consumption in suspend mode (max. 2.5mA on Vbus): * - \code void user_callback_suspend_action(void) - { - turn_off_components(); - } \endcode + { + turn_off_components(); + } \endcode */ /** @@ -654,44 +647,42 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_6_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_SERIAL_NAME - #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number - #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 - extern uint8_t serial_number[]; + #define USB_DEVICE_SERIAL_NAME + #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number + #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 + extern uint8_t serial_number[]; \endcode * * Add to application C-file: * \code - uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; + uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; - void init_build_usb_serial_number(void) - { - serial_number[0] = 'A'; - serial_number[1] = 'B'; - ... - serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; - } \endcode + void init_build_usb_serial_number(void) + { + serial_number[0] = 'A'; + serial_number[1] = 'B'; + ... + serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; + } \endcode * * \subsection udc_use_case_6_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable a USB serial number strings dynamically: * - \code #define USB_DEVICE_SERIAL_NAME // Define this empty - #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer - #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array - extern uint8_t serial_number[]; // Declare external serial array \endcode + #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer + #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array + extern uint8_t serial_number[]; // Declare external serial array \endcode * -# Before start USB stack, initialize the serial array * - \code - uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; + uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; - void init_build_usb_serial_number(void) - { - serial_number[0] = 'A'; - serial_number[1] = 'B'; - ... - serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; - } \endcode + void init_build_usb_serial_number(void) + { + serial_number[0] = 'A'; + serial_number[1] = 'B'; + ... + serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; + } \endcode */ - - #endif // _UDC_H_ diff --git a/Marlin/src/HAL/DUE/usb/udc_desc.h b/Marlin/src/HAL/DUE/usb/udc_desc.h index 052ca08eca..f1f328d035 100644 --- a/Marlin/src/HAL/DUE/usb/udc_desc.h +++ b/Marlin/src/HAL/DUE/usb/udc_desc.h @@ -78,50 +78,47 @@ extern "C" { * For Mega application used "code". */ #define UDC_DESC_STORAGE - // Descriptor storage in internal RAM + // Descriptor storage in internal RAM #if (defined UDC_DATA_USE_HRAM_SUPPORT) -# if defined(__GNUC__) -# define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0"))) -# define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0"))) -# elif defined(__ICCAVR32__) -# define UDC_DATA(x) COMPILER_ALIGNED(x) __data32 -# define UDC_BSS(x) COMPILER_ALIGNED(x) __data32 -# endif -#else -# define UDC_DATA(x) COMPILER_ALIGNED(x) -# define UDC_BSS(x) COMPILER_ALIGNED(x) + #if defined(__GNUC__) + #define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0"))) + #define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0"))) +#elif defined(__ICCAVR32__) + #define UDC_DATA(x) COMPILER_ALIGNED(x) __data32 + #define UDC_BSS(x) COMPILER_ALIGNED(x) __data32 +#endif +#else + #define UDC_DATA(x) COMPILER_ALIGNED(x) + #define UDC_BSS(x) COMPILER_ALIGNED(x) #endif - - /** * \brief Configuration descriptor and UDI link for one USB speed */ typedef struct { - //! USB configuration descriptor - usb_conf_desc_t UDC_DESC_STORAGE *desc; - //! Array of UDI API pointer - udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis; + //! USB configuration descriptor + usb_conf_desc_t UDC_DESC_STORAGE *desc; + //! Array of UDI API pointer + udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis; } udc_config_speed_t; - /** * \brief All information about the USB Device */ typedef struct { - //! USB device descriptor for low or full speed - usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs; - //! USB configuration descriptor and UDI API pointers for low or full speed - udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs; -#ifdef USB_DEVICE_HS_SUPPORT - //! USB device descriptor for high speed - usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs; - //! USB device qualifier, only use in high speed mode - usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier; - //! USB configuration descriptor and UDI API pointers for high speed - udc_config_speed_t UDC_DESC_STORAGE *conf_hs; -#endif - usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos; + //! USB device descriptor for low or full speed + usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs; + //! USB configuration descriptor and UDI API pointers for low or full speed + udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs; + #ifdef USB_DEVICE_HS_SUPPORT + //! USB device descriptor for high speed + usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs; + //! USB device qualifier, only use in high speed mode + usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier; + //! USB configuration descriptor and UDI API pointers for high speed + udc_config_speed_t UDC_DESC_STORAGE *conf_hs; + #endif + usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos; } udc_config_t; //! Global variables of USB Device Descriptor and UDI links diff --git a/Marlin/src/HAL/DUE/usb/udd.h b/Marlin/src/HAL/DUE/usb/udd.h index 319d8842f7..4e482784e1 100644 --- a/Marlin/src/HAL/DUE/usb/udd.h +++ b/Marlin/src/HAL/DUE/usb/udd.h @@ -71,8 +71,8 @@ typedef uint8_t udd_ep_id_t; //! \brief Endpoint transfer status //! Returned in parameters of callback register via udd_ep_run routine. typedef enum { - UDD_EP_TRANSFER_OK = 0, - UDD_EP_TRANSFER_ABORT = 1, + UDD_EP_TRANSFER_OK = 0, + UDD_EP_TRANSFER_ABORT = 1, } udd_ep_status_t; /** @@ -82,41 +82,37 @@ typedef enum { * It can be updated by udc_process_setup() from UDC or *setup() from UDIs. */ typedef struct { - //! Data received in USB SETUP packet - //! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD. - usb_setup_req_t req; + //! Data received in USB SETUP packet + //! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD. + usb_setup_req_t req; - //! Point to buffer to send or fill with data following SETUP packet - //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) - uint8_t *payload; + //! Point to buffer to send or fill with data following SETUP packet + //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) + uint8_t *payload; - //! Size of buffer to send or fill, and content the number of byte transferred - uint16_t payload_size; + //! Size of buffer to send or fill, and content the number of byte transferred + uint16_t payload_size; - //! Callback called after reception of ZLP from setup request - void (*callback)(void); + //! Callback called after reception of ZLP from setup request + void (*callback)(void); - //! Callback called when the buffer given (.payload) is full or empty. - //! This one return false to abort data transfer, or true with a new buffer in .payload. - bool (*over_under_run)(void); + //! Callback called when the buffer given (.payload) is full or empty. + //! This one return false to abort data transfer, or true with a new buffer in .payload. + bool (*over_under_run)(void); } udd_ctrl_request_t; extern udd_ctrl_request_t udd_g_ctrlreq; //! Return true if the setup request \a udd_g_ctrlreq indicates IN data transfer -#define Udd_setup_is_in() \ - (USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) +#define Udd_setup_is_in() (USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) //! Return true if the setup request \a udd_g_ctrlreq indicates OUT data transfer -#define Udd_setup_is_out() \ - (USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) +#define Udd_setup_is_out() (USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) //! Return the type of the SETUP request \a udd_g_ctrlreq. \see usb_reqtype. -#define Udd_setup_type() \ - (udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK) +#define Udd_setup_type() (udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK) //! Return the recipient of the SETUP request \a udd_g_ctrlreq. \see usb_recipient -#define Udd_setup_recipient() \ - (udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK) +#define Udd_setup_recipient() (udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK) /** * \brief End of halt callback function type. @@ -134,8 +130,7 @@ typedef void (*udd_callback_halt_cleared_t)(void); * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted * \param n number of data transferred */ -typedef void (*udd_callback_trans_t) (udd_ep_status_t status, - iram_size_t nb_transferred, udd_ep_id_t ep); +typedef void (*udd_callback_trans_t) (udd_ep_status_t status, iram_size_t nb_transferred, udd_ep_id_t ep); /** * \brief Authorizes the VBUS event @@ -218,7 +213,6 @@ void udd_send_remotewakeup(void); */ void udd_set_setup_payload( uint8_t *payload, uint16_t payload_size ); - /** * \name Endpoint Management * @@ -239,8 +233,7 @@ void udd_set_setup_payload( uint8_t *payload, uint16_t payload_size ); * * \return \c 1 if the endpoint is enabled, otherwise \c 0. */ -bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, - uint16_t MaxEndpointSize); +bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, uint16_t MaxEndpointSize); /** * \brief Disables an endpoint @@ -294,8 +287,7 @@ bool udd_ep_clear_halt(udd_ep_id_t ep); * * \return \c 1 if the register is accepted, otherwise \c 0. */ -bool udd_ep_wait_stall_clear(udd_ep_id_t ep, - udd_callback_halt_cleared_t callback); +bool udd_ep_wait_stall_clear(udd_ep_id_t ep, udd_callback_halt_cleared_t callback); /** * \brief Allows to receive or send data on an endpoint @@ -321,9 +313,8 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, * * \return \c 1 if function was successfully done, otherwise \c 0. */ -bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, - uint8_t * buf, iram_size_t buf_size, - udd_callback_trans_t callback); +bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, uint8_t * buf, iram_size_t buf_size, udd_callback_trans_t callback); + /** * \brief Aborts transfer on going on endpoint * @@ -339,7 +330,6 @@ void udd_ep_abort(udd_ep_id_t ep); //@} - /** * \name High speed test mode management * @@ -352,7 +342,6 @@ void udd_test_mode_se0_nak(void); void udd_test_mode_packet(void); //@} - /** * \name UDC callbacks to provide for UDD * diff --git a/Marlin/src/HAL/DUE/usb/udi.h b/Marlin/src/HAL/DUE/usb/udi.h index febf03b718..bc5de086f3 100644 --- a/Marlin/src/HAL/DUE/usb/udi.h +++ b/Marlin/src/HAL/DUE/usb/udi.h @@ -72,57 +72,57 @@ extern "C" { * selected by UDC. */ typedef struct { - /** - * \brief Enable the interface. - * - * This function is called when the host selects a configuration - * to which this interface belongs through a Set Configuration - * request, and when the host selects an alternate setting of - * this interface through a Set Interface request. - * - * \return \c 1 if function was successfully done, otherwise \c 0. - */ - bool (*enable)(void); + /** + * \brief Enable the interface. + * + * This function is called when the host selects a configuration + * to which this interface belongs through a Set Configuration + * request, and when the host selects an alternate setting of + * this interface through a Set Interface request. + * + * \return \c 1 if function was successfully done, otherwise \c 0. + */ + bool (*enable)(void); - /** - * \brief Disable the interface. - * - * This function is called when this interface is currently - * active, and - * - the host selects any configuration through a Set - * Configuration request, or - * - the host issues a USB reset, or - * - the device is detached from the host (i.e. Vbus is no - * longer present) - */ - void (*disable)(void); + /** + * \brief Disable the interface. + * + * This function is called when this interface is currently + * active, and + * - the host selects any configuration through a Set + * Configuration request, or + * - the host issues a USB reset, or + * - the device is detached from the host (i.e. Vbus is no + * longer present) + */ + void (*disable)(void); - /** - * \brief Handle a control request directed at an interface. - * - * This function is called when this interface is currently - * active and the host sends a SETUP request - * with this interface as the recipient. - * - * Use udd_g_ctrlreq to decode and response to SETUP request. - * - * \return \c 1 if this interface supports the SETUP request, otherwise \c 0. - */ - bool (*setup)(void); + /** + * \brief Handle a control request directed at an interface. + * + * This function is called when this interface is currently + * active and the host sends a SETUP request + * with this interface as the recipient. + * + * Use udd_g_ctrlreq to decode and response to SETUP request. + * + * \return \c 1 if this interface supports the SETUP request, otherwise \c 0. + */ + bool (*setup)(void); - /** - * \brief Returns the current setting of the selected interface. - * - * This function is called when UDC when know alternate setting of selected interface. - * - * \return alternate setting of selected interface - */ - uint8_t (*getsetting)(void); + /** + * \brief Returns the current setting of the selected interface. + * + * This function is called when UDC when know alternate setting of selected interface. + * + * \return alternate setting of selected interface + */ + uint8_t (*getsetting)(void); - /** - * \brief To signal that a SOF is occurred - */ - void (*sof_notify)(void); + /** + * \brief To signal that a SOF is occurred + */ + void (*sof_notify)(void); } udi_api_t; //@} diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.c b/Marlin/src/HAL/DUE/usb/udi_cdc.c index 89debe57f1..26788570c6 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.c +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.c @@ -457,7 +457,6 @@ void udi_cdc_data_sof_notify(void) #endif } - // ------------------------ //------- Internal routines to control serial line @@ -520,7 +519,6 @@ static void udi_cdc_ctrl_state_change(uint8_t port, bool b_set, le16_t bit_mask) udi_cdc_ctrl_state_notify(port, ep_comm); } - static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep) { #if UDI_CDC_PORT_NB == 1 // To optimize code @@ -542,7 +540,6 @@ static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep) } } - static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t port; @@ -578,11 +575,9 @@ static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udi_cdc_ctrl_state_notify(port, ep); } - // ------------------------ //------- Internal routines to process data transfer - static bool udi_cdc_rx_start(uint8_t port) { irqflags_t flags; @@ -632,7 +627,6 @@ static bool udi_cdc_rx_start(uint8_t port) udi_cdc_data_received); } - static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t buf_sel_trans; @@ -668,7 +662,6 @@ static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_ udi_cdc_rx_start(port); } - static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t port; @@ -700,7 +693,6 @@ static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t udi_cdc_tx_send(port); } - static void udi_cdc_tx_send(uint8_t port) { irqflags_t flags; @@ -780,11 +772,9 @@ static void udi_cdc_tx_send(uint8_t port) udi_cdc_data_sent); } - // ------------------------ //------- Application interface - //------- Application interface void udi_cdc_ctrl_signal_dcd(bool b_set) diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.h b/Marlin/src/HAL/DUE/usb/udi_cdc.h index b61845011a..e9c6abbbb2 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.h +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.h @@ -92,21 +92,20 @@ extern UDC_DESC_STORAGE udi_api_t udi_api_cdc_data; * descriptors for the CDC Communication Class interface. */ typedef struct { - //! Standard interface descriptor - usb_iface_desc_t iface; - //! CDC Header functional descriptor - usb_cdc_hdr_desc_t header; - //! CDC Abstract Control Model functional descriptor - usb_cdc_acm_desc_t acm; - //! CDC Union functional descriptor - usb_cdc_union_desc_t union_desc; - //! CDC Call Management functional descriptor - usb_cdc_call_mgmt_desc_t call_mgmt; - //! Notification endpoint descriptor - usb_ep_desc_t ep_notify; + //! Standard interface descriptor + usb_iface_desc_t iface; + //! CDC Header functional descriptor + usb_cdc_hdr_desc_t header; + //! CDC Abstract Control Model functional descriptor + usb_cdc_acm_desc_t acm; + //! CDC Union functional descriptor + usb_cdc_union_desc_t union_desc; + //! CDC Call Management functional descriptor + usb_cdc_call_mgmt_desc_t call_mgmt; + //! Notification endpoint descriptor + usb_ep_desc_t ep_notify; } udi_cdc_comm_desc_t; - /** * \brief Data Class interface descriptor * @@ -114,14 +113,13 @@ typedef struct { * CDC Data Class interface. */ typedef struct { - //! Standard interface descriptor - usb_iface_desc_t iface; - //! Data IN/OUT endpoint descriptors - usb_ep_desc_t ep_in; - usb_ep_desc_t ep_out; + //! Standard interface descriptor + usb_iface_desc_t iface; + //! Data IN/OUT endpoint descriptors + usb_ep_desc_t ep_in; + usb_ep_desc_t ep_out; } udi_cdc_data_desc_t; - //! CDC communication endpoints size for all speeds #define UDI_CDC_COMM_EP_SIZE 64 //! CDC data endpoints size for FS speed (8B, 16B, 32B, 64B) @@ -136,13 +134,13 @@ typedef struct { //@{ //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_0 -#define UDI_CDC_IAD_STRING_ID_0 0 + #define UDI_CDC_IAD_STRING_ID_0 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_0 -#define UDI_CDC_COMM_STRING_ID_0 0 + #define UDI_CDC_COMM_STRING_ID_0 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_0 -#define UDI_CDC_DATA_STRING_ID_0 0 + #define UDI_CDC_DATA_STRING_ID_0 0 #endif #define UDI_CDC_IAD_DESC_0 UDI_CDC_IAD_DESC(0) #define UDI_CDC_COMM_DESC_0 UDI_CDC_COMM_DESC(0) @@ -151,13 +149,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_1 -#define UDI_CDC_IAD_STRING_ID_1 0 + #define UDI_CDC_IAD_STRING_ID_1 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_1 -#define UDI_CDC_COMM_STRING_ID_1 0 + #define UDI_CDC_COMM_STRING_ID_1 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_1 -#define UDI_CDC_DATA_STRING_ID_1 0 + #define UDI_CDC_DATA_STRING_ID_1 0 #endif #define UDI_CDC_IAD_DESC_1 UDI_CDC_IAD_DESC(1) #define UDI_CDC_COMM_DESC_1 UDI_CDC_COMM_DESC(1) @@ -166,13 +164,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_2 -#define UDI_CDC_IAD_STRING_ID_2 0 + #define UDI_CDC_IAD_STRING_ID_2 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_2 -#define UDI_CDC_COMM_STRING_ID_2 0 + #define UDI_CDC_COMM_STRING_ID_2 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_2 -#define UDI_CDC_DATA_STRING_ID_2 0 + #define UDI_CDC_DATA_STRING_ID_2 0 #endif #define UDI_CDC_IAD_DESC_2 UDI_CDC_IAD_DESC(2) #define UDI_CDC_COMM_DESC_2 UDI_CDC_COMM_DESC(2) @@ -181,13 +179,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_3 -#define UDI_CDC_IAD_STRING_ID_3 0 + #define UDI_CDC_IAD_STRING_ID_3 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_3 -#define UDI_CDC_COMM_STRING_ID_3 0 + #define UDI_CDC_COMM_STRING_ID_3 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_3 -#define UDI_CDC_DATA_STRING_ID_3 0 + #define UDI_CDC_DATA_STRING_ID_3 0 #endif #define UDI_CDC_IAD_DESC_3 UDI_CDC_IAD_DESC(3) #define UDI_CDC_COMM_DESC_3 UDI_CDC_COMM_DESC(3) @@ -196,13 +194,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_4 -#define UDI_CDC_IAD_STRING_ID_4 0 + #define UDI_CDC_IAD_STRING_ID_4 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_4 -#define UDI_CDC_COMM_STRING_ID_4 0 + #define UDI_CDC_COMM_STRING_ID_4 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_4 -#define UDI_CDC_DATA_STRING_ID_4 0 + #define UDI_CDC_DATA_STRING_ID_4 0 #endif #define UDI_CDC_IAD_DESC_4 UDI_CDC_IAD_DESC(4) #define UDI_CDC_COMM_DESC_4 UDI_CDC_COMM_DESC(4) @@ -211,13 +209,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_5 -#define UDI_CDC_IAD_STRING_ID_5 0 + #define UDI_CDC_IAD_STRING_ID_5 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_5 -#define UDI_CDC_COMM_STRING_ID_5 0 + #define UDI_CDC_COMM_STRING_ID_5 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_5 -#define UDI_CDC_DATA_STRING_ID_5 0 + #define UDI_CDC_DATA_STRING_ID_5 0 #endif #define UDI_CDC_IAD_DESC_5 UDI_CDC_IAD_DESC(5) #define UDI_CDC_COMM_DESC_5 UDI_CDC_COMM_DESC(5) @@ -226,13 +224,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_6 -#define UDI_CDC_IAD_STRING_ID_6 0 + #define UDI_CDC_IAD_STRING_ID_6 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_6 -#define UDI_CDC_COMM_STRING_ID_6 0 + #define UDI_CDC_COMM_STRING_ID_6 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_6 -#define UDI_CDC_DATA_STRING_ID_6 0 + #define UDI_CDC_DATA_STRING_ID_6 0 #endif #define UDI_CDC_IAD_DESC_6 UDI_CDC_IAD_DESC(6) #define UDI_CDC_COMM_DESC_6 UDI_CDC_COMM_DESC(6) @@ -240,7 +238,6 @@ typedef struct { #define UDI_CDC_DATA_DESC_6_HS UDI_CDC_DATA_DESC_HS(6) //@} - //! Content of CDC IAD interface descriptor for all speeds #define UDI_CDC_IAD_DESC(port) { \ .bLength = sizeof(usb_iad_desc_t),\ @@ -270,7 +267,7 @@ typedef struct { .call_mgmt.bDescriptorType = CDC_CS_INTERFACE,\ .call_mgmt.bDescriptorSubtype = CDC_SCS_CALL_MGMT,\ .call_mgmt.bmCapabilities = \ - CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\ + CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\ .acm.bFunctionLength = sizeof(usb_cdc_acm_desc_t),\ .acm.bDescriptorType = CDC_CS_INTERFACE,\ .acm.bDescriptorSubtype = CDC_SCS_ACM,\ @@ -610,40 +607,37 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \subsection udi_cdc_basic_use_case_usage_code Example code * Content of conf_usb.h: * \code - #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() - extern bool my_callback_cdc_enable(void); - #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() - extern void my_callback_cdc_disable(void); - #define UDI_CDC_LOW_RATE + #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() + extern bool my_callback_cdc_enable(void); + #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() + extern void my_callback_cdc_disable(void); + #define UDI_CDC_LOW_RATE - #define UDI_CDC_DEFAULT_RATE 115200 - #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 - #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE - #define UDI_CDC_DEFAULT_DATABITS 8 + #define UDI_CDC_DEFAULT_RATE 115200 + #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 + #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE + #define UDI_CDC_DEFAULT_DATABITS 8 - #include "udi_cdc_conf.h" // At the end of conf_usb.h file + #include "udi_cdc_conf.h" // At the end of conf_usb.h file \endcode * * Add to application C-file: * \code - static bool my_flag_autorize_cdc_transfert = false; - bool my_callback_cdc_enable(void) - { - my_flag_autorize_cdc_transfert = true; - return true; - } - void my_callback_cdc_disable(void) - { - my_flag_autorize_cdc_transfert = false; - } + static bool my_flag_autorize_cdc_transfert = false; + bool my_callback_cdc_enable(void) { + my_flag_autorize_cdc_transfert = true; + return true; + } + void my_callback_cdc_disable(void) { + my_flag_autorize_cdc_transfert = false; + } - void task(void) - { - if (my_flag_autorize_cdc_transfert) { - udi_cdc_putc('A'); - udi_cdc_getc(); - } - } + void task(void) { + if (my_flag_autorize_cdc_transfert) { + udi_cdc_putc('A'); + udi_cdc_getc(); + } + } \endcode * * \subsection udi_cdc_basic_use_case_setup_flow Workflow @@ -652,14 +646,14 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for CDC \endcode * \note The USB serial number is mandatory when a CDC interface is used. * - \code #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() - extern bool my_callback_cdc_enable(void); \endcode + extern bool my_callback_cdc_enable(void); \endcode * \note After the device enumeration (detecting and identifying USB devices), * the USB host starts the device configuration. When the USB CDC interface * from the device is accepted by the host, the USB host enables this interface and the * UDI_CDC_ENABLE_EXT() callback function is called and return true. * Thus, when this event is received, the data transfer on CDC interface are authorized. * - \code #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() - extern void my_callback_cdc_disable(void); \endcode + extern void my_callback_cdc_disable(void); \endcode * \note When the USB device is unplugged or is reset by the USB host, the USB * interface is disabled and the UDI_CDC_DISABLE_EXT() callback function * is called. Thus, the data transfer must be stopped on CDC interface. @@ -667,19 +661,19 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \note Define it when the transfer CDC Device to Host is a low rate * (<512000 bauds) to reduce CDC buffers size. * - \code #define UDI_CDC_DEFAULT_RATE 115200 - #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 - #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE - #define UDI_CDC_DEFAULT_DATABITS 8 \endcode + #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 + #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE + #define UDI_CDC_DEFAULT_DATABITS 8 \endcode * \note Default configuration of communication port at startup. * -# Send or wait data on CDC line: * - \code // Waits and gets a value on CDC line - int udi_cdc_getc(void); - // Reads a RAM buffer on CDC line - iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size); - // Puts a byte on CDC line - int udi_cdc_putc(int value); - // Writes a RAM buffer on CDC line - iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode + int udi_cdc_getc(void); + // Reads a RAM buffer on CDC line + iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size); + // Puts a byte on CDC line + int udi_cdc_putc(int value); + // Writes a RAM buffer on CDC line + iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode * * \section udi_cdc_use_cases Advanced use cases * For more advanced use of the UDI CDC module, see the following use cases: @@ -713,90 +707,90 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \subsection udi_cdc_use_case_composite_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_EP_CTRL_SIZE 64 - #define USB_DEVICE_NB_INTERFACE (X+2) - #define USB_DEVICE_MAX_EP (X+3) + #define USB_DEVICE_EP_CTRL_SIZE 64 + #define USB_DEVICE_NB_INTERFACE (X+2) + #define USB_DEVICE_MAX_EP (X+3) - #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX - #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX - #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint - #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 - #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 + #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX + #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX + #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint + #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 + #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 - #define UDI_COMPOSITE_DESC_T \ - usb_iad_desc_t udi_cdc_iad; \ - udi_cdc_comm_desc_t udi_cdc_comm; \ - udi_cdc_data_desc_t udi_cdc_data; \ - ... - #define UDI_COMPOSITE_DESC_FS \ - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ - ... - #define UDI_COMPOSITE_DESC_HS \ - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ - ... - #define UDI_COMPOSITE_API \ - &udi_api_cdc_comm, \ - &udi_api_cdc_data, \ - ... + #define UDI_COMPOSITE_DESC_T \ + usb_iad_desc_t udi_cdc_iad; \ + udi_cdc_comm_desc_t udi_cdc_comm; \ + udi_cdc_data_desc_t udi_cdc_data; \ + ... + #define UDI_COMPOSITE_DESC_FS \ + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ + ... + #define UDI_COMPOSITE_DESC_HS \ + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ + ... + #define UDI_COMPOSITE_API \ + &udi_api_cdc_comm, \ + &udi_api_cdc_data, \ + ... \endcode * * \subsection udi_cdc_use_case_composite_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB composite device configuration: * - \code // Endpoint control size, This must be: - // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) - // - 64 for a high speed device - #define USB_DEVICE_EP_CTRL_SIZE 64 - // Total Number of interfaces on this USB device. - // Add 2 for CDC. - #define USB_DEVICE_NB_INTERFACE (X+2) - // Total number of endpoints on this USB device. - // This must include each endpoint for each interface. - // Add 3 for CDC. - #define USB_DEVICE_MAX_EP (X+3) \endcode + // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) + // - 64 for a high speed device + #define USB_DEVICE_EP_CTRL_SIZE 64 + // Total Number of interfaces on this USB device. + // Add 2 for CDC. + #define USB_DEVICE_NB_INTERFACE (X+2) + // Total number of endpoints on this USB device. + // This must include each endpoint for each interface. + // Add 3 for CDC. + #define USB_DEVICE_MAX_EP (X+3) \endcode * -# Ensure that conf_usb.h contains the description of * composite device: * - \code // The endpoint numbers chosen by you for the CDC. - // The endpoint numbers starting from 1. - #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX - #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX - #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint - // The interface index of an interface starting from 0 - #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 - #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode + // The endpoint numbers starting from 1. + #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX + #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX + #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint + // The interface index of an interface starting from 0 + #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 + #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB composite device configuration: * - \code // USB Interfaces descriptor structure - #define UDI_COMPOSITE_DESC_T \ - ... - usb_iad_desc_t udi_cdc_iad; \ - udi_cdc_comm_desc_t udi_cdc_comm; \ - udi_cdc_data_desc_t udi_cdc_data; \ - ... - // USB Interfaces descriptor value for Full Speed - #define UDI_COMPOSITE_DESC_FS \ - ... - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ - ... - // USB Interfaces descriptor value for High Speed - #define UDI_COMPOSITE_DESC_HS \ - ... - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ - ... - // USB Interface APIs - #define UDI_COMPOSITE_API \ - ... - &udi_api_cdc_comm, \ - &udi_api_cdc_data, \ - ... \endcode + #define UDI_COMPOSITE_DESC_T \ + ... + usb_iad_desc_t udi_cdc_iad; \ + udi_cdc_comm_desc_t udi_cdc_comm; \ + udi_cdc_data_desc_t udi_cdc_data; \ + ... + // USB Interfaces descriptor value for Full Speed + #define UDI_COMPOSITE_DESC_FS \ + ... + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ + ... + // USB Interfaces descriptor value for High Speed + #define UDI_COMPOSITE_DESC_HS \ + ... + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ + ... + // USB Interface APIs + #define UDI_COMPOSITE_API \ + ... + &udi_api_cdc_comm, \ + &udi_api_cdc_data, \ + ... \endcode * - \note The descriptors order given in the four lists above must be the * same as the order defined by all interface indexes. The interface index * orders are defined through UDI_X_IFACE_NUMBER defines.\n diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c b/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c index 97c334e2a8..bcae362cef 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c +++ b/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c @@ -51,7 +51,7 @@ #include "udc_desc.h" #include "udi_cdc.h" -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA /** * \defgroup udi_cdc_group_single_desc USB device descriptors for a single interface @@ -109,7 +109,6 @@ UDC_DESC_STORAGE usb_dev_desc_t udc_device_desc = { .bNumConfigurations = 1 }; - #ifdef USB_DEVICE_HS_SUPPORT //! USB Device Qualifier Descriptor for HS COMPILER_WORD_ALIGNED @@ -256,6 +255,6 @@ UDC_DESC_STORAGE udc_config_t udc_config = { //@} //@} -#endif // SDSUPPORT +#endif // HAS_MEDIA #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/usb/udi_composite_desc.c b/Marlin/src/HAL/DUE/usb/udi_composite_desc.c index da74fbe60d..8fa5acbb3f 100644 --- a/Marlin/src/HAL/DUE/usb/udi_composite_desc.c +++ b/Marlin/src/HAL/DUE/usb/udi_composite_desc.c @@ -50,7 +50,7 @@ #include "udd.h" #include "udc_desc.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA /** * \defgroup udi_group_desc Descriptors for a USB Device @@ -93,7 +93,6 @@ UDC_DESC_STORAGE usb_dev_desc_t udc_device_desc = { .bNumConfigurations = 1 }; - #ifdef USB_DEVICE_HS_SUPPORT //! USB Device Qualifier Descriptor for HS COMPILER_WORD_ALIGNED @@ -147,7 +146,6 @@ UDC_DESC_STORAGE udc_desc_t udc_desc_hs = { }; #endif - /** * \name UDC structures which contains all USB Device definitions */ @@ -189,4 +187,4 @@ UDC_DESC_STORAGE udc_config_t udc_config = { #endif // ARDUINO_ARCH_SAM -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.c b/Marlin/src/HAL/DUE/usb/udi_msc.c index dd34048772..56664f4bf7 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.c +++ b/Marlin/src/HAL/DUE/usb/udi_msc.c @@ -57,7 +57,7 @@ #include "ctrl_access.h" #include -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #ifndef UDI_MSC_NOTIFY_TRANS_EXT # define UDI_MSC_NOTIFY_TRANS_EXT() @@ -86,7 +86,6 @@ UDC_DESC_STORAGE udi_api_t udi_api_msc = { }; //@} - /** * \ingroup udi_msc_group * \defgroup udi_msc_group_internal Implementation of UDI MSC @@ -137,7 +136,6 @@ volatile bool udi_msc_b_reset_trans = true; //@} - /** * \name Internal routines */ @@ -190,7 +188,6 @@ static void udi_msc_cbw_received(udd_ep_status_t status, static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag); //@} - /** * \name Routines to process small data packet */ @@ -217,7 +214,6 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); //@} - /** * \name Routines to process CSW packet */ @@ -250,7 +246,6 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); //@} - /** * \name Routines manage sense data */ @@ -307,7 +302,6 @@ static void udi_msc_sense_fail_cdb_invalid(void); static void udi_msc_sense_command_invalid(void); //@} - /** * \name Routines manage SCSI Commands */ @@ -372,9 +366,7 @@ static void udi_msc_sbc_trans(bool b_read); //@} - -bool udi_msc_enable(void) -{ +bool udi_msc_enable(void) { uint8_t lun; udi_msc_b_trans_req = false; udi_msc_b_cbw_invalid = false; @@ -397,18 +389,14 @@ bool udi_msc_enable(void) return true; } - -void udi_msc_disable(void) -{ +void udi_msc_disable(void) { udi_msc_b_trans_req = false; udi_msc_b_ack_trans = true; udi_msc_b_reset_trans = true; UDI_MSC_DISABLE_EXT(); } - -bool udi_msc_setup(void) -{ +bool udi_msc_setup(void) { if (Udd_setup_is_in()) { // Requests Interface GET if (Udd_setup_type() == USB_REQ_TYPE_CLASS) { @@ -451,17 +439,14 @@ bool udi_msc_setup(void) return false; // Not supported request } -uint8_t udi_msc_getsetting(void) -{ +uint8_t udi_msc_getsetting(void) { return 0; // MSC don't have multiple alternate setting } - // ------------------------ //------- Routines to process CBW packet -static void udi_msc_cbw_invalid(void) -{ +static void udi_msc_cbw_invalid(void) { if (!udi_msc_b_cbw_invalid) return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_OUT); @@ -469,8 +454,7 @@ static void udi_msc_cbw_invalid(void) udd_ep_wait_stall_clear(UDI_MSC_EP_OUT, udi_msc_cbw_invalid); } -static void udi_msc_csw_invalid(void) -{ +static void udi_msc_csw_invalid(void) { if (!udi_msc_b_cbw_invalid) return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_IN); @@ -478,8 +462,7 @@ static void udi_msc_csw_invalid(void) udd_ep_wait_stall_clear(UDI_MSC_EP_IN, udi_msc_csw_invalid); } -static void udi_msc_cbw_wait(void) -{ +static void udi_msc_cbw_wait(void) { // Register buffer and callback on OUT endpoint if (!udd_ep_run(UDI_MSC_EP_OUT, true, (uint8_t *) & udi_msc_cbw, @@ -490,10 +473,8 @@ static void udi_msc_cbw_wait(void) } } - static void udi_msc_cbw_received(udd_ep_status_t status, - iram_size_t nb_received, udd_ep_id_t ep) -{ + iram_size_t nb_received, udd_ep_id_t ep) { UNUSED(ep); // Check status of transfer if (UDD_EP_TRANSFER_OK != status) { @@ -582,9 +563,7 @@ static void udi_msc_cbw_received(udd_ep_status_t status, } } - -static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) -{ +static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) { /* * The following cases should result in a phase error: * - Case 2: Hn < Di @@ -612,12 +591,10 @@ static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) return true; } - // ------------------------ //------- Routines to process small data packet -static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) -{ +static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) { // Sends data on IN endpoint if (!udd_ep_run(UDI_MSC_EP_IN, true, buffer, buf_size, udi_msc_data_sent)) { @@ -627,10 +604,8 @@ static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) } } - static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); if (UDD_EP_TRANSFER_OK != status) { // Error protocol @@ -644,12 +619,10 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udi_msc_csw_process(); } - // ------------------------ //------- Routines to process CSW packet -static void udi_msc_csw_process(void) -{ +static void udi_msc_csw_process(void) { if (0 != udi_msc_csw.dCSWDataResidue) { // Residue not NULL // then STALL next request from USB host on corresponding endpoint @@ -664,9 +637,7 @@ static void udi_msc_csw_process(void) udi_msc_csw_send(); } - -void udi_msc_csw_send(void) -{ +void udi_msc_csw_send(void) { // Sends CSW on IN endpoint if (!udd_ep_run(UDI_MSC_EP_IN, false, (uint8_t *) & udi_msc_csw, @@ -678,10 +649,8 @@ void udi_msc_csw_send(void) } } - static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); UNUSED(status); UNUSED(nb_sent); @@ -690,20 +659,17 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udi_msc_cbw_wait(); } - // ------------------------ //------- Routines manage sense data -static void udi_msc_clear_sense(void) -{ +static void udi_msc_clear_sense(void) { memset((uint8_t*)&udi_msc_sense, 0, sizeof(struct scsi_request_sense_data)); udi_msc_sense.valid_reponse_code = SCSI_SENSE_VALID | SCSI_SENSE_CURRENT; udi_msc_sense.AddSenseLen = SCSI_SENSE_ADDL_LEN(sizeof(udi_msc_sense)); } static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense, - uint32_t lba) -{ + uint32_t lba) { udi_msc_clear_sense(); udi_msc_csw.bCSWStatus = USB_CSW_STATUS_FAIL; udi_msc_sense.sense_flag_key = sense_key; @@ -715,53 +681,39 @@ static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense, udi_msc_sense.AddSnsCodeQlfr = add_sense; } -static void udi_msc_sense_pass(void) -{ +static void udi_msc_sense_pass(void) { udi_msc_clear_sense(); udi_msc_csw.bCSWStatus = USB_CSW_STATUS_PASS; } - -static void udi_msc_sense_fail_not_present(void) -{ +static void udi_msc_sense_fail_not_present(void) { udi_msc_sense_fail(SCSI_SK_NOT_READY, SCSI_ASC_MEDIUM_NOT_PRESENT, 0); } -static void udi_msc_sense_fail_busy_or_change(void) -{ - udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, - SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); +static void udi_msc_sense_fail_busy_or_change(void) { + udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); } -static void udi_msc_sense_fail_hardware(void) -{ - udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, - SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); +static void udi_msc_sense_fail_hardware(void) { + udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); } -static void udi_msc_sense_fail_protected(void) -{ +static void udi_msc_sense_fail_protected(void) { udi_msc_sense_fail(SCSI_SK_DATA_PROTECT, SCSI_ASC_WRITE_PROTECTED, 0); } -static void udi_msc_sense_fail_cdb_invalid(void) -{ - udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, - SCSI_ASC_INVALID_FIELD_IN_CDB, 0); +static void udi_msc_sense_fail_cdb_invalid(void) { + udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, SCSI_ASC_INVALID_FIELD_IN_CDB, 0); } -static void udi_msc_sense_command_invalid(void) -{ - udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, - SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); +static void udi_msc_sense_command_invalid(void) { + udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); } - // ------------------------ //------- Routines manage SCSI Commands -static void udi_msc_spc_requestsense(void) -{ +static void udi_msc_spc_requestsense(void) { uint8_t length = udi_msc_cbw.CDB[4]; // Can't send more than sense data length @@ -774,9 +726,7 @@ static void udi_msc_spc_requestsense(void) udi_msc_data_send((uint8_t*)&udi_msc_sense, length); } - -static void udi_msc_spc_inquiry(void) -{ +static void udi_msc_spc_inquiry(void) { uint8_t length, i; UDC_DATA(4) // Constant inquiry data for all LUNs @@ -835,9 +785,7 @@ static void udi_msc_spc_inquiry(void) udi_msc_data_send((uint8_t *) & udi_msc_inquiry_data, length); } - -static bool udi_msc_spc_testunitready_global(void) -{ +static bool udi_msc_spc_testunitready_global(void) { switch (mem_test_unit_ready(udi_msc_cbw.bCBWLUN)) { case CTRL_GOOD: return true; // Don't change sense data @@ -855,9 +803,7 @@ static bool udi_msc_spc_testunitready_global(void) return false; } - -static void udi_msc_spc_testunitready(void) -{ +static void udi_msc_spc_testunitready(void) { if (udi_msc_spc_testunitready_global()) { // LUN ready, then update sense data with status pass udi_msc_sense_pass(); @@ -866,9 +812,7 @@ static void udi_msc_spc_testunitready(void) udi_msc_csw_process(); } - -static void udi_msc_spc_mode_sense(bool b_sense10) -{ +static void udi_msc_spc_mode_sense(bool b_sense10) { // Union of all mode sense structures union sense_6_10 { struct { @@ -943,9 +887,7 @@ static void udi_msc_spc_mode_sense(bool b_sense10) udi_msc_data_send((uint8_t *) & sense, request_lgt); } - -static void udi_msc_spc_prevent_allow_medium_removal(void) -{ +static void udi_msc_spc_prevent_allow_medium_removal(void) { uint8_t prevent = udi_msc_cbw.CDB[4]; if (0 == prevent) { udi_msc_sense_pass(); @@ -955,9 +897,7 @@ static void udi_msc_spc_prevent_allow_medium_removal(void) udi_msc_csw_process(); } - -static void udi_msc_sbc_start_stop(void) -{ +static void udi_msc_sbc_start_stop(void) { bool start = 0x1 & udi_msc_cbw.CDB[4]; bool loej = 0x2 & udi_msc_cbw.CDB[4]; if (loej) { @@ -967,9 +907,7 @@ static void udi_msc_sbc_start_stop(void) udi_msc_csw_process(); } - -static void udi_msc_sbc_read_capacity(void) -{ +static void udi_msc_sbc_read_capacity(void) { UDC_BSS(4) static struct sbc_read_capacity10_data udi_msc_capacity; if (!udi_msc_cbw_validate(sizeof(udi_msc_capacity), @@ -1003,9 +941,7 @@ static void udi_msc_sbc_read_capacity(void) sizeof(udi_msc_capacity)); } - -static void udi_msc_sbc_trans(bool b_read) -{ +static void udi_msc_sbc_trans(bool b_read) { uint32_t trans_size; if (!b_read) { @@ -1038,9 +974,7 @@ static void udi_msc_sbc_trans(bool b_read) UDI_MSC_NOTIFY_TRANS_EXT(); } - -bool udi_msc_process_trans(void) -{ +bool udi_msc_process_trans(void) { Ctrl_status status; if (!udi_msc_b_trans_req) @@ -1084,10 +1018,8 @@ bool udi_msc_process_trans(void) return true; } - static void udi_msc_trans_ack(udd_ep_status_t status, iram_size_t n, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); UNUSED(n); // Update variable to signal the end of transfer @@ -1095,10 +1027,8 @@ static void udi_msc_trans_ack(udd_ep_status_t status, iram_size_t n, udi_msc_b_ack_trans = true; } - bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, - void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)) -{ + void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)) { if (!udi_msc_b_ack_trans) return false; // No possible, transfer on going @@ -1127,6 +1057,6 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, //@} -#endif // SDSUPPORT +#endif // HAS_MEDIA #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.h b/Marlin/src/HAL/DUE/usb/udi_msc.h index 730dbc8eec..0ede4d6a83 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.h +++ b/Marlin/src/HAL/DUE/usb/udi_msc.h @@ -77,9 +77,9 @@ extern UDC_DESC_STORAGE udi_api_t udi_api_msc; //! Interface descriptor structure for MSC typedef struct { - usb_iface_desc_t iface; - usb_ep_desc_t ep_in; - usb_ep_desc_t ep_out; + usb_iface_desc_t iface; + usb_ep_desc_t ep_in; + usb_ep_desc_t ep_out; } udi_msc_desc_t; //! By default no string associated to this interface @@ -94,32 +94,32 @@ typedef struct { //! Content of MSC interface descriptor for all speeds #define UDI_MSC_DESC \ - .iface.bLength = sizeof(usb_iface_desc_t),\ - .iface.bDescriptorType = USB_DT_INTERFACE,\ - .iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\ - .iface.bAlternateSetting = 0,\ - .iface.bNumEndpoints = 2,\ - .iface.bInterfaceClass = MSC_CLASS,\ - .iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\ - .iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\ - .iface.iInterface = UDI_MSC_STRING_ID,\ - .ep_in.bLength = sizeof(usb_ep_desc_t),\ - .ep_in.bDescriptorType = USB_DT_ENDPOINT,\ - .ep_in.bEndpointAddress = UDI_MSC_EP_IN,\ - .ep_in.bmAttributes = USB_EP_TYPE_BULK,\ - .ep_in.bInterval = 0,\ - .ep_out.bLength = sizeof(usb_ep_desc_t),\ - .ep_out.bDescriptorType = USB_DT_ENDPOINT,\ - .ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\ - .ep_out.bmAttributes = USB_EP_TYPE_BULK,\ - .ep_out.bInterval = 0, + .iface.bLength = sizeof(usb_iface_desc_t),\ + .iface.bDescriptorType = USB_DT_INTERFACE,\ + .iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\ + .iface.bAlternateSetting = 0,\ + .iface.bNumEndpoints = 2,\ + .iface.bInterfaceClass = MSC_CLASS,\ + .iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\ + .iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\ + .iface.iInterface = UDI_MSC_STRING_ID,\ + .ep_in.bLength = sizeof(usb_ep_desc_t),\ + .ep_in.bDescriptorType = USB_DT_ENDPOINT,\ + .ep_in.bEndpointAddress = UDI_MSC_EP_IN,\ + .ep_in.bmAttributes = USB_EP_TYPE_BULK,\ + .ep_in.bInterval = 0,\ + .ep_out.bLength = sizeof(usb_ep_desc_t),\ + .ep_out.bDescriptorType = USB_DT_ENDPOINT,\ + .ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\ + .ep_out.bmAttributes = USB_EP_TYPE_BULK,\ + .ep_out.bInterval = 0, //! Content of MSC interface descriptor for full speed only #define UDI_MSC_DESC_FS {\ - UDI_MSC_DESC \ - .ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ - .ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ - } + UDI_MSC_DESC \ + .ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ + .ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ + } //! Content of MSC interface descriptor for high speed only #define UDI_MSC_DESC_HS {\ @@ -129,7 +129,6 @@ typedef struct { } //@} - /** * \ingroup udi_group * \defgroup udi_msc_group USB Device Interface (UDI) for Mass Storage Class (MSC) @@ -163,14 +162,13 @@ bool udi_msc_process_trans(void); * \return \c 1 if function was successfully done, otherwise \c 0. */ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, - void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)); + void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)); //@} #ifdef __cplusplus } #endif - /** * \page udi_msc_quickstart Quick start guide for USB device Mass Storage module (UDI MSC) * @@ -200,35 +198,32 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \subsection udi_msc_basic_use_case_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC - #define UDI_MSC_GLOBAL_VENDOR_ID \ - 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' - #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ - '1', '.', '0', '0' - #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() - extern bool my_callback_msc_enable(void); - #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() - extern void my_callback_msc_disable(void); - #include "udi_msc_conf.h" // At the end of conf_usb.h file + #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC + #define UDI_MSC_GLOBAL_VENDOR_ID \ + 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' + #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ + '1', '.', '0', '0' + #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() + extern bool my_callback_msc_enable(void); + #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() + extern void my_callback_msc_disable(void); + #include "udi_msc_conf.h" // At the end of conf_usb.h file \endcode * * Add to application C-file: * \code - static bool my_flag_autorize_msc_transfert = false; - bool my_callback_msc_enable(void) - { - my_flag_autorize_msc_transfert = true; - return true; - } - void my_callback_msc_disable(void) - { - my_flag_autorize_msc_transfert = false; - } + static bool my_flag_autorize_msc_transfert = false; + bool my_callback_msc_enable(void) { + my_flag_autorize_msc_transfert = true; + return true; + } + void my_callback_msc_disable(void) { + my_flag_autorize_msc_transfert = false; + } - void task(void) - { - udi_msc_process_trans(); - } + void task(void) { + udi_msc_process_trans(); + } \endcode * * \subsection udi_msc_basic_use_case_setup_flow Workflow @@ -237,14 +232,14 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC \endcode * \note The USB serial number is mandatory when a MSC interface is used. * - \code //! Vendor name and Product version of MSC interface - #define UDI_MSC_GLOBAL_VENDOR_ID \ - 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' - #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ - '1', '.', '0', '0' \endcode + #define UDI_MSC_GLOBAL_VENDOR_ID \ + 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' + #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ + '1', '.', '0', '0' \endcode * \note The USB MSC interface requires a vendor ID (8 ASCII characters) * and a product version (4 ASCII characters). * - \code #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() - extern bool my_callback_msc_enable(void); \endcode + extern bool my_callback_msc_enable(void); \endcode * \note After the device enumeration (detecting and identifying USB devices), * the USB host starts the device configuration. When the USB MSC interface * from the device is accepted by the host, the USB host enables this interface and the @@ -252,7 +247,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * Thus, when this event is received, the tasks which call * udi_msc_process_trans() must be enabled. * - \code #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() - extern void my_callback_msc_disable(void); \endcode + extern void my_callback_msc_disable(void); \endcode * \note When the USB device is unplugged or is reset by the USB host, the USB * interface is disabled and the UDI_MSC_DISABLE_EXT() callback function * is called. Thus, it is recommended to disable the task which is called udi_msc_process_trans(). @@ -261,15 +256,15 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * must be done outside USB interrupt routine. This is done in the MSC process * ("udi_msc_process_trans()") called by main loop: * - \code * void task(void) { - udi_msc_process_trans(); - } \endcode + udi_msc_process_trans(); + } \endcode * -# The MSC speed depends on task periodicity. To get the best speed * the notification callback "UDI_MSC_NOTIFY_TRANS_EXT" can be used to wakeup * this task (Example, through a mutex): * - \code #define UDI_MSC_NOTIFY_TRANS_EXT() msc_notify_trans() - void msc_notify_trans(void) { - wakeup_my_task(); - } \endcode + void msc_notify_trans(void) { + wakeup_my_task(); + } \endcode * * \section udi_msc_use_cases Advanced use cases * For more advanced use of the UDI MSC module, see the following use cases: @@ -302,72 +297,72 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \subsection udi_msc_use_case_composite_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_EP_CTRL_SIZE 64 - #define USB_DEVICE_NB_INTERFACE (X+1) - #define USB_DEVICE_MAX_EP (X+2) + #define USB_DEVICE_EP_CTRL_SIZE 64 + #define USB_DEVICE_NB_INTERFACE (X+1) + #define USB_DEVICE_MAX_EP (X+2) - #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) - #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) - #define UDI_MSC_IFACE_NUMBER X + #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) + #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) + #define UDI_MSC_IFACE_NUMBER X - #define UDI_COMPOSITE_DESC_T \ - udi_msc_desc_t udi_msc; \ - ... - #define UDI_COMPOSITE_DESC_FS \ - .udi_msc = UDI_MSC_DESC, \ - ... - #define UDI_COMPOSITE_DESC_HS \ - .udi_msc = UDI_MSC_DESC, \ - ... - #define UDI_COMPOSITE_API \ - &udi_api_msc, \ - ... + #define UDI_COMPOSITE_DESC_T \ + udi_msc_desc_t udi_msc; \ + ... + #define UDI_COMPOSITE_DESC_FS \ + .udi_msc = UDI_MSC_DESC, \ + ... + #define UDI_COMPOSITE_DESC_HS \ + .udi_msc = UDI_MSC_DESC, \ + ... + #define UDI_COMPOSITE_API \ + &udi_api_msc, \ + ... \endcode * * \subsection udi_msc_use_case_composite_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB composite device configuration: * - \code // Endpoint control size, This must be: - // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) - // - 64 for a high speed device - #define USB_DEVICE_EP_CTRL_SIZE 64 - // Total Number of interfaces on this USB device. - // Add 1 for MSC. - #define USB_DEVICE_NB_INTERFACE (X+1) - // Total number of endpoints on this USB device. - // This must include each endpoint for each interface. - // Add 2 for MSC. - #define USB_DEVICE_MAX_EP (X+2) \endcode + // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) + // - 64 for a high speed device + #define USB_DEVICE_EP_CTRL_SIZE 64 + // Total Number of interfaces on this USB device. + // Add 1 for MSC. + #define USB_DEVICE_NB_INTERFACE (X+1) + // Total number of endpoints on this USB device. + // This must include each endpoint for each interface. + // Add 2 for MSC. + #define USB_DEVICE_MAX_EP (X+2) \endcode * -# Ensure that conf_usb.h contains the description of * composite device: * - \code // The endpoint numbers chosen by you for the MSC. - // The endpoint numbers starting from 1. - #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) - #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) - // The interface index of an interface starting from 0 - #define UDI_MSC_IFACE_NUMBER X \endcode + // The endpoint numbers starting from 1. + #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) + #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) + // The interface index of an interface starting from 0 + #define UDI_MSC_IFACE_NUMBER X \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB composite device configuration: * - \code // USB Interfaces descriptor structure - #define UDI_COMPOSITE_DESC_T \ - ... - udi_msc_desc_t udi_msc; \ - ... - // USB Interfaces descriptor value for Full Speed - #define UDI_COMPOSITE_DESC_FS \ - ... - .udi_msc = UDI_MSC_DESC_FS, \ - ... - // USB Interfaces descriptor value for High Speed - #define UDI_COMPOSITE_DESC_HS \ - ... - .udi_msc = UDI_MSC_DESC_HS, \ - ... - // USB Interface APIs - #define UDI_COMPOSITE_API \ - ... - &udi_api_msc, \ - ... \endcode + #define UDI_COMPOSITE_DESC_T \ + ... + udi_msc_desc_t udi_msc; \ + ... + // USB Interfaces descriptor value for Full Speed + #define UDI_COMPOSITE_DESC_FS \ + ... + .udi_msc = UDI_MSC_DESC_FS, \ + ... + // USB Interfaces descriptor value for High Speed + #define UDI_COMPOSITE_DESC_HS \ + ... + .udi_msc = UDI_MSC_DESC_HS, \ + ... + // USB Interface APIs + #define UDI_COMPOSITE_API \ + ... + &udi_api_msc, \ + ... \endcode * - \note The descriptors order given in the four lists above must be the * same as the order defined by all interface indexes. The interface index * orders are defined through UDI_X_IFACE_NUMBER defines. diff --git a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c index c7e8f8d991..5635f2ba0c 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c +++ b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c @@ -116,6 +116,23 @@ //#define dbg_print printf #define dbg_print(...) +// Marlin modification: Redefine the otg_freeze_clock and otg_unfreeze_clock macros +// to add memory barriers to ensure that any accesses to USB registers aren't re-ordered +// to occur while the clock is frozen. +#undef otg_freeze_clock +#undef otg_unfreeze_clock + +#define otg_freeze_clock() do { \ + __DSB(); \ + Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_FRZCLK); \ +} while (0) + +#define otg_unfreeze_clock() \ +do { \ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_FRZCLK); \ + __DSB(); \ +} while (0) + /** * \ingroup udd_group * \defgroup udd_udphs_group USB On-The-Go High-Speed Port for device mode (UOTGHS) @@ -276,7 +293,6 @@ # endif #endif - /** * \name Power management routine. */ @@ -293,7 +309,6 @@ static bool udd_b_idle; //! State of sleep manager static bool udd_b_sleep_initialized = false; - /*! \brief Authorize or not the CPU powerdown mode * * \param b_enable true to authorize idle mode @@ -321,7 +336,6 @@ static void udd_sleep_mode(bool b_idle) //@} - /** * \name Control endpoint low level management routine. * @@ -393,7 +407,6 @@ static void udd_ctrl_send_zlp_out(void); //! \brief Call callback associated to setup request static void udd_ctrl_endofrequest(void); - /** * \brief Main interrupt routine for control endpoint * @@ -405,7 +418,6 @@ static bool udd_ctrl_interrupt(void); //@} - /** * \name Management of bulk/interrupt/isochronous endpoints * @@ -443,7 +455,6 @@ typedef struct { uint8_t stall_requested:1; } udd_ep_job_t; - //! Array to register a job on bulk/interrupt/isochronous endpoint static udd_ep_job_t udd_ep_job[USB_DEVICE_MAX_EP]; @@ -505,7 +516,6 @@ static bool udd_ep_interrupt(void); #endif // (0!=USB_DEVICE_MAX_EP) //@} - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED GLOBAL EVENTS @@ -513,7 +523,7 @@ static bool udd_ep_interrupt(void); * \internal * \brief Function called by UOTGHS interrupt to manage USB Device interrupts * - * USB Device interrupt events are splited in three parts: + * USB Device interrupt events are split in three parts: * - USB line events (SOF, reset, suspend, resume, wakeup) * - control endpoint events (setup reception, end of data transfer, underflow, overflow, stall) * - bulk/interrupt/isochronous endpoints events (end of data transfer) @@ -611,6 +621,18 @@ ISR(UDD_USB_INT_FUN) // The wakeup interrupt is automatic acked when a suspend occur udd_disable_wake_up_interrupt(); udd_enable_suspend_interrupt(); + + // Marlin modification: The RESET, SOF, and MSOF interrupts were previously + // enabled in udd_attach, which caused a race condition where they could + // be raised and unclearable with the clock is frozen. They are now + // enabled here, after the clock has been unfrozen in response to the wake + // interrupt. + udd_enable_reset_interrupt(); + udd_enable_sof_interrupt(); +#ifdef USB_DEVICE_HS_SUPPORT + udd_enable_msof_interrupt(); +#endif + udd_sleep_mode(true); // Enter in IDLE mode #ifdef UDC_RESUME_EVENT UDC_RESUME_EVENT(); @@ -642,13 +664,11 @@ udd_interrupt_sof_end: return; } - bool udd_include_vbus_monitoring(void) { return true; } - void udd_enable(void) { irqflags_t flags; @@ -735,7 +755,6 @@ void udd_enable(void) cpu_irq_restore(flags); } - void udd_disable(void) { irqflags_t flags; @@ -776,6 +795,27 @@ void udd_disable(void) cpu_irq_restore(flags); } +// Marlin modification: The original implementation did not use a memory +// barrier between disabling and clearing interrupts. This sometimes +// allowed interrupts to remain raised and unclearable after the clock +// was frozen. This helper was added to ensure that memory barriers +// are used consistently from all places where interrupts are disabled. +static void disable_and_ack_sync_interrupts() +{ + // Disable USB line events + udd_disable_reset_interrupt(); + udd_disable_sof_interrupt(); +#ifdef USB_DEVICE_HS_SUPPORT + udd_disable_msof_interrupt(); +#endif + __DSB(); + udd_ack_reset(); + udd_ack_sof(); +#ifdef USB_DEVICE_HS_SUPPORT + udd_ack_msof(); +#endif + __DSB(); +} void udd_attach(void) { @@ -796,17 +836,16 @@ void udd_attach(void) udd_attach_device(); // Enable USB line events - udd_enable_reset_interrupt(); udd_enable_suspend_interrupt(); udd_enable_wake_up_interrupt(); - udd_enable_sof_interrupt(); -#ifdef USB_DEVICE_HS_SUPPORT - udd_enable_msof_interrupt(); -#endif - // Reset following interrupts flag - udd_ack_reset(); - udd_ack_sof(); - udd_ack_msof(); + + // Marlin modification: The RESET, SOF, and MSOF interrupts were previously + // enabled here, which caused a race condition where they could be raised + // and unclearable with the clock is frozen. They are now enabled in the + // wake interrupt handler, after the clock has been unfrozen. They are now + // explicitly disabled here to ensure that they cannot be raised before + // the clock is frozen. + disable_and_ack_sync_interrupts(); // The first suspend interrupt must be forced // The first suspend interrupt is not detected else raise it @@ -817,18 +856,22 @@ void udd_attach(void) cpu_irq_restore(flags); } - void udd_detach(void) { otg_unfreeze_clock(); // Detach device from the bus udd_detach_device(); + + // Marlin modification: Added the explicit disabling of the RESET, SOF, and + // MSOF interrupts here, to ensure that they cannot be raised after the + // clock is frozen. + disable_and_ack_sync_interrupts(); + otg_freeze_clock(); udd_sleep_mode(false); } - bool udd_is_high_speed(void) { #ifdef USB_DEVICE_HS_SUPPORT @@ -838,7 +881,6 @@ bool udd_is_high_speed(void) #endif } - void udd_set_address(uint8_t address) { udd_disable_address(); @@ -846,13 +888,11 @@ void udd_set_address(uint8_t address) udd_enable_address(); } - uint8_t udd_getaddress(void) { return udd_get_configured_address(); } - uint16_t udd_get_frame_number(void) { return udd_frame_number(); @@ -875,14 +915,12 @@ void udd_send_remotewakeup(void) } } - void udd_set_setup_payload(uint8_t *payload, uint16_t payload_size) { udd_g_ctrlreq.payload = payload; udd_g_ctrlreq.payload_size = payload_size; } - #if (0 != USB_DEVICE_MAX_EP) bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, uint16_t MaxEndpointSize) @@ -1006,7 +1044,6 @@ bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, return true; } - void udd_ep_free(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1019,14 +1056,12 @@ void udd_ep_free(udd_ep_id_t ep) udd_ep_job[ep_index - 1].stall_requested = false; } - bool udd_ep_is_halted(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; return Is_udd_endpoint_stall_requested(ep_index); } - bool udd_ep_set_halt(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1067,7 +1102,6 @@ bool udd_ep_set_halt(udd_ep_id_t ep) return true; } - bool udd_ep_clear_halt(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1108,7 +1142,6 @@ bool udd_ep_clear_halt(udd_ep_id_t ep) return true; } - bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, uint8_t * buf, iram_size_t buf_size, udd_callback_trans_t callback) @@ -1175,7 +1208,6 @@ bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, #endif } - void udd_ep_abort(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1204,7 +1236,6 @@ void udd_ep_abort(udd_ep_id_t ep) udd_ep_abort_job(ep); } - bool udd_ep_wait_stall_clear(udd_ep_id_t ep, udd_callback_halt_cleared_t callback) { @@ -1239,7 +1270,6 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, } #endif // (0 != USB_DEVICE_MAX_EP) - #ifdef USB_DEVICE_HS_SUPPORT void udd_test_mode_j(void) @@ -1248,20 +1278,17 @@ void udd_test_mode_j(void) udd_enable_hs_test_mode_j(); } - void udd_test_mode_k(void) { udd_enable_hs_test_mode(); udd_enable_hs_test_mode_k(); } - void udd_test_mode_se0_nak(void) { udd_enable_hs_test_mode(); } - void udd_test_mode_packet(void) { uint8_t i; @@ -1305,8 +1332,6 @@ void udd_test_mode_packet(void) } #endif // USB_DEVICE_HS_SUPPORT - - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED THE CONTROL ENDPOINT @@ -1356,7 +1381,6 @@ static void udd_ctrl_init(void) udd_ep_control_state = UDD_EPCTRL_SETUP; } - static void udd_ctrl_setup_received(void) { irqflags_t flags; @@ -1418,7 +1442,6 @@ static void udd_ctrl_setup_received(void) } } - static void udd_ctrl_in_sent(void) { static bool b_shortpacket = false; @@ -1502,7 +1525,6 @@ static void udd_ctrl_in_sent(void) cpu_irq_restore(flags); } - static void udd_ctrl_out_received(void) { irqflags_t flags; @@ -1545,7 +1567,7 @@ static void udd_ctrl_out_received(void) udd_ctrl_payload_buf_cnt))) { // End of reception because it is a short packet // Before send ZLP, call intermediate callback - // in case of data receiv generate a stall + // in case of data receive generate a stall udd_g_ctrlreq.payload_size = udd_ctrl_payload_buf_cnt; if (NULL != udd_g_ctrlreq.over_under_run) { if (!udd_g_ctrlreq.over_under_run()) { @@ -1593,7 +1615,6 @@ static void udd_ctrl_out_received(void) cpu_irq_restore(flags); } - static void udd_ctrl_underflow(void) { if (Is_udd_out_received(0)) @@ -1610,7 +1631,6 @@ static void udd_ctrl_underflow(void) } } - static void udd_ctrl_overflow(void) { if (Is_udd_in_send(0)) @@ -1626,7 +1646,6 @@ static void udd_ctrl_overflow(void) } } - static void udd_ctrl_stall_data(void) { // Stall all packets on IN & OUT control endpoint @@ -1634,7 +1653,6 @@ static void udd_ctrl_stall_data(void) udd_enable_stall_handshake(0); } - static void udd_ctrl_send_zlp_in(void) { irqflags_t flags; @@ -1652,7 +1670,6 @@ static void udd_ctrl_send_zlp_in(void) cpu_irq_restore(flags); } - static void udd_ctrl_send_zlp_out(void) { irqflags_t flags; @@ -1668,7 +1685,6 @@ static void udd_ctrl_send_zlp_out(void) cpu_irq_restore(flags); } - static void udd_ctrl_endofrequest(void) { // If a callback is registered then call it @@ -1677,7 +1693,6 @@ static void udd_ctrl_endofrequest(void) } } - static bool udd_ctrl_interrupt(void) { @@ -1728,7 +1743,6 @@ static bool udd_ctrl_interrupt(void) return false; } - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED THE BULK/INTERRUPT/ISOCHRONOUS ENDPOINTS @@ -1743,7 +1757,6 @@ static void udd_ep_job_table_reset(void) } } - static void udd_ep_job_table_kill(void) { uint8_t i; @@ -1754,7 +1767,6 @@ static void udd_ep_job_table_kill(void) } } - static void udd_ep_abort_job(udd_ep_id_t ep) { ep &= USB_EP_ADDR_MASK; @@ -1763,7 +1775,6 @@ static void udd_ep_abort_job(udd_ep_id_t ep) udd_ep_finish_job(&udd_ep_job[ep - 1], true, ep); } - static void udd_ep_finish_job(udd_ep_job_t * ptr_job, bool b_abort, uint8_t ep_num) { if (ptr_job->busy == false) { @@ -1797,7 +1808,7 @@ static void udd_ep_trans_done(udd_ep_id_t ep) } if (ptr_job->buf_cnt != ptr_job->buf_size) { - // Need to send or receiv other data + // Need to send or receive other data next_trans = ptr_job->buf_size - ptr_job->buf_cnt; if (UDD_ENDPOINT_MAX_TRANS < next_trans) { @@ -1834,7 +1845,6 @@ static void udd_ep_trans_done(udd_ep_id_t ep) udd_dma_ctrl |= UOTGHS_DEVDMACONTROL_END_BUFFIT | UOTGHS_DEVDMACONTROL_CHANN_ENB; - // Disable IRQs to have a short sequence // between read of EOT_STA and DMA enable flags = cpu_irq_save(); @@ -2043,6 +2053,12 @@ static bool udd_ep_interrupt(void) dbg_print("I "); udd_disable_in_send_interrupt(ep); // One bank is free then send a ZLP + + // Marlin modification: Add a barrier to ensure in_send is disabled + // before it is cleared. This was not an observed problem, but + // other interrupts were seen to misbehave without this barrier. + __DSB(); + udd_ack_in_send(ep); udd_ack_fifocon(ep); udd_ep_finish_job(ptr_job, false, ep); diff --git a/Marlin/src/HAL/DUE/usb/uotghs_device_due.h b/Marlin/src/HAL/DUE/usb/uotghs_device_due.h index 6df26d63df..99ad492c1f 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_device_due.h +++ b/Marlin/src/HAL/DUE/usb/uotghs_device_due.h @@ -129,7 +129,6 @@ extern "C" { #define Is_udd_vbus_transition() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_VBUSTI)) //! @} - //! @name UOTGHS device attach control //! These macros manage the UOTGHS Device attach. //! @{ @@ -141,7 +140,6 @@ extern "C" { #define Is_udd_detached() (Tst_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_DETACH)) //! @} - //! @name UOTGHS device bus events control //! These macros manage the UOTGHS Device bus events. //! @{ @@ -246,7 +244,6 @@ extern "C" { #define udd_get_configured_address() (Rd_bitfield(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_UADD_Msk)) //! @} - //! @name UOTGHS Device endpoint drivers //! These macros manage the common features of the endpoints. //! @{ @@ -330,7 +327,6 @@ extern "C" { #define udd_data_toggle(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_DTSEQ_Msk)) //! @} - //! @name UOTGHS Device control endpoint //! These macros control the endpoints. //! @{ @@ -530,7 +526,6 @@ extern "C" { //! Tests if IN sending interrupt is enabled #define Is_udd_in_send_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_TXINE)) - //! Get 64-, 32-, 16- or 8-bit access to FIFO data register of selected endpoint. //! @param ep Endpoint of which to access FIFO data register //! @param scale Data scale in bits: 64, 32, 16 or 8 @@ -652,7 +647,6 @@ typedef struct { //! @} //! @} - /// @cond 0 /**INDENT-OFF**/ #ifdef __cplusplus diff --git a/Marlin/src/HAL/DUE/usb/uotghs_otg.h b/Marlin/src/HAL/DUE/usb/uotghs_otg.h index eca5e938bb..8c12a3e291 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_otg.h +++ b/Marlin/src/HAL/DUE/usb/uotghs_otg.h @@ -53,7 +53,6 @@ extern "C" { #endif - //! \ingroup usb_group //! \defgroup otg_group UOTGHS OTG Driver //! UOTGHS low-level driver for OTG features @@ -74,7 +73,6 @@ bool otg_dual_enable(void); */ void otg_dual_disable(void); - //! @name UOTGHS OTG ID pin management //! The ID pin come from the USB OTG connector (A and B receptable) and //! allows to select the USB mode host or device. @@ -127,13 +125,13 @@ void otg_dual_disable(void); //! These macros allows to enable/disable pad and UOTGHS hardware //! @{ //! Reset USB macro -#define otg_reset() \ - do { \ - UOTGHS->UOTGHS_CTRL = 0; \ - while( UOTGHS->UOTGHS_SR & 0x3FFF) {\ - UOTGHS->UOTGHS_SCR = 0xFFFFFFFF;\ - } \ - } while (0) +#define otg_reset() \ + do { \ + UOTGHS->UOTGHS_CTRL = 0; \ + while( UOTGHS->UOTGHS_SR & 0x3FFF) { \ + UOTGHS->UOTGHS_SCR = 0xFFFFFFFF; \ + } \ + } while (0) //! Enable USB macro #define otg_enable() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE)) //! Disable USB macro @@ -157,15 +155,14 @@ void otg_dual_disable(void); //! Configure time-out of specified OTG timer #define otg_configure_timeout(timer, timeout) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\ - Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK)) + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK)) //! Get configured time-out of specified OTG timer #define otg_get_timeout(timer) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ - Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk)) - + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ + Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk)) //! Get the dual-role device state of the internal USB finite state machine of the UOTGHS controller #define otg_get_fsm_drd_state() (Rd_bitfield(UOTGHS->UOTGHS_FSM, UOTGHS_FSM_DRDSTATE_Msk)) diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol.h b/Marlin/src/HAL/DUE/usb/usb_protocol.h index ea51a86896..9bf0a1ba60 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol.h @@ -108,17 +108,17 @@ * \brief Standard USB requests (bRequest) */ enum usb_reqid { - USB_REQ_GET_STATUS = 0, - USB_REQ_CLEAR_FEATURE = 1, - USB_REQ_SET_FEATURE = 3, - USB_REQ_SET_ADDRESS = 5, - USB_REQ_GET_DESCRIPTOR = 6, - USB_REQ_SET_DESCRIPTOR = 7, - USB_REQ_GET_CONFIGURATION = 8, - USB_REQ_SET_CONFIGURATION = 9, - USB_REQ_GET_INTERFACE = 10, - USB_REQ_SET_INTERFACE = 11, - USB_REQ_SYNCH_FRAME = 12, + USB_REQ_GET_STATUS = 0, + USB_REQ_CLEAR_FEATURE = 1, + USB_REQ_SET_FEATURE = 3, + USB_REQ_SET_ADDRESS = 5, + USB_REQ_GET_DESCRIPTOR = 6, + USB_REQ_SET_DESCRIPTOR = 7, + USB_REQ_GET_CONFIGURATION = 8, + USB_REQ_SET_CONFIGURATION = 9, + USB_REQ_GET_INTERFACE = 10, + USB_REQ_SET_INTERFACE = 11, + USB_REQ_SYNCH_FRAME = 12, }; /** @@ -126,9 +126,9 @@ enum usb_reqid { * */ enum usb_device_status { - USB_DEV_STATUS_BUS_POWERED = 0, - USB_DEV_STATUS_SELF_POWERED = 1, - USB_DEV_STATUS_REMOTEWAKEUP = 2 + USB_DEV_STATUS_BUS_POWERED = 0, + USB_DEV_STATUS_SELF_POWERED = 1, + USB_DEV_STATUS_REMOTEWAKEUP = 2 }; /** @@ -136,7 +136,7 @@ enum usb_device_status { * */ enum usb_interface_status { - USB_IFACE_STATUS_RESERVED = 0 + USB_IFACE_STATUS_RESERVED = 0 }; /** @@ -144,7 +144,7 @@ enum usb_interface_status { * */ enum usb_endpoint_status { - USB_EP_STATUS_HALTED = 1, + USB_EP_STATUS_HALTED = 1, }; /** @@ -153,11 +153,11 @@ enum usb_endpoint_status { * \note valid for SetFeature request. */ enum usb_device_feature { - USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled - USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode - USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3, - USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4, - USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5 + USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled + USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode + USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3, + USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4, + USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5 }; /** @@ -166,54 +166,54 @@ enum usb_device_feature { * \note valid for USB_DEV_FEATURE_TEST_MODE request. */ enum usb_device_hs_test_mode { - USB_DEV_TEST_MODE_J = 1, - USB_DEV_TEST_MODE_K = 2, - USB_DEV_TEST_MODE_SE0_NAK = 3, - USB_DEV_TEST_MODE_PACKET = 4, - USB_DEV_TEST_MODE_FORCE_ENABLE = 5, + USB_DEV_TEST_MODE_J = 1, + USB_DEV_TEST_MODE_K = 2, + USB_DEV_TEST_MODE_SE0_NAK = 3, + USB_DEV_TEST_MODE_PACKET = 4, + USB_DEV_TEST_MODE_FORCE_ENABLE = 5, }; /** * \brief Standard USB endpoint feature/status flags */ enum usb_endpoint_feature { - USB_EP_FEATURE_HALT = 0, + USB_EP_FEATURE_HALT = 0, }; /** * \brief Standard USB Test Mode Selectors */ enum usb_test_mode_selector { - USB_TEST_J = 0x01, - USB_TEST_K = 0x02, - USB_TEST_SE0_NAK = 0x03, - USB_TEST_PACKET = 0x04, - USB_TEST_FORCE_ENABLE = 0x05, + USB_TEST_J = 0x01, + USB_TEST_K = 0x02, + USB_TEST_SE0_NAK = 0x03, + USB_TEST_PACKET = 0x04, + USB_TEST_FORCE_ENABLE = 0x05, }; /** * \brief Standard USB descriptor types */ enum usb_descriptor_type { - USB_DT_DEVICE = 1, - USB_DT_CONFIGURATION = 2, - USB_DT_STRING = 3, - USB_DT_INTERFACE = 4, - USB_DT_ENDPOINT = 5, - USB_DT_DEVICE_QUALIFIER = 6, - USB_DT_OTHER_SPEED_CONFIGURATION = 7, - USB_DT_INTERFACE_POWER = 8, - USB_DT_OTG = 9, - USB_DT_IAD = 0x0B, - USB_DT_BOS = 0x0F, - USB_DT_DEVICE_CAPABILITY = 0x10, + USB_DT_DEVICE = 1, + USB_DT_CONFIGURATION = 2, + USB_DT_STRING = 3, + USB_DT_INTERFACE = 4, + USB_DT_ENDPOINT = 5, + USB_DT_DEVICE_QUALIFIER = 6, + USB_DT_OTHER_SPEED_CONFIGURATION = 7, + USB_DT_INTERFACE_POWER = 8, + USB_DT_OTG = 9, + USB_DT_IAD = 0x0B, + USB_DT_BOS = 0x0F, + USB_DT_DEVICE_CAPABILITY = 0x10, }; /** * \brief USB Device Capability types */ enum usb_capability_type { - USB_DC_USB20_EXTENSION = 0x02, + USB_DC_USB20_EXTENSION = 0x02, }; /** @@ -221,7 +221,7 @@ enum usb_capability_type { * To fill bmAttributes field of usb_capa_ext_desc_t structure. */ enum usb_capability_extension_attr { - USB_DC_EXT_LPM = 0x00000002, + USB_DC_EXT_LPM = 0x00000002, }; #define HIRD_50_US 0 @@ -254,18 +254,18 @@ enum usb_capability_extension_attr { * \brief Standard USB endpoint transfer types */ enum usb_ep_type { - USB_EP_TYPE_CONTROL = 0x00, - USB_EP_TYPE_ISOCHRONOUS = 0x01, - USB_EP_TYPE_BULK = 0x02, - USB_EP_TYPE_INTERRUPT = 0x03, - USB_EP_TYPE_MASK = 0x03, + USB_EP_TYPE_CONTROL = 0x00, + USB_EP_TYPE_ISOCHRONOUS = 0x01, + USB_EP_TYPE_BULK = 0x02, + USB_EP_TYPE_INTERRUPT = 0x03, + USB_EP_TYPE_MASK = 0x03, }; /** * \brief Standard USB language IDs for string descriptors */ enum usb_langid { - USB_LANGID_EN_US = 0x0409, //!< English (United States) + USB_LANGID_EN_US = 0x0409, //!< English (United States) }; /** @@ -308,31 +308,31 @@ COMPILER_PACK_SET(1) * The data payload of SETUP packets always follows this structure. */ typedef struct { - uint8_t bmRequestType; - uint8_t bRequest; - le16_t wValue; - le16_t wIndex; - le16_t wLength; + uint8_t bmRequestType; + uint8_t bRequest; + le16_t wValue; + le16_t wIndex; + le16_t wLength; } usb_setup_req_t; /** * \brief Standard USB device descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t bcdUSB; - uint8_t bDeviceClass; - uint8_t bDeviceSubClass; - uint8_t bDeviceProtocol; - uint8_t bMaxPacketSize0; - le16_t idVendor; - le16_t idProduct; - le16_t bcdDevice; - uint8_t iManufacturer; - uint8_t iProduct; - uint8_t iSerialNumber; - uint8_t bNumConfigurations; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + le16_t idVendor; + le16_t idProduct; + le16_t bcdDevice; + uint8_t iManufacturer; + uint8_t iProduct; + uint8_t iSerialNumber; + uint8_t bNumConfigurations; } usb_dev_desc_t; /** @@ -344,15 +344,15 @@ typedef struct { * the device was operating at full speed.) */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t bcdUSB; - uint8_t bDeviceClass; - uint8_t bDeviceSubClass; - uint8_t bDeviceProtocol; - uint8_t bMaxPacketSize0; - uint8_t bNumConfigurations; - uint8_t bReserved; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + uint8_t bNumConfigurations; + uint8_t bReserved; } usb_dev_qual_desc_t; /** @@ -368,23 +368,22 @@ typedef struct { * The descriptor type in the GetDescriptor() request is set to BOS. */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t wTotalLength; - uint8_t bNumDeviceCaps; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t wTotalLength; + uint8_t bNumDeviceCaps; } usb_dev_bos_desc_t; - /** * \brief USB Device Capabilities - USB 2.0 Extension Descriptor structure * * Defines the set of USB 1.1-specific device level capabilities. */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bDevCapabilityType; - le32_t bmAttributes; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bDevCapabilityType; + le32_t bmAttributes; } usb_dev_capa_ext_desc_t; /** @@ -393,40 +392,38 @@ typedef struct { * The BOS descriptor and capabilities descriptors for LPM. */ typedef struct { - usb_dev_bos_desc_t bos; - usb_dev_capa_ext_desc_t capa_ext; + usb_dev_bos_desc_t bos; + usb_dev_capa_ext_desc_t capa_ext; } usb_dev_lpm_desc_t; /** * \brief Standard USB Interface Association Descriptor structure */ typedef struct { - uint8_t bLength; //!< size of this descriptor in bytes - uint8_t bDescriptorType; //!< INTERFACE descriptor type - uint8_t bFirstInterface; //!< Number of interface - uint8_t bInterfaceCount; //!< value to select alternate setting - uint8_t bFunctionClass; //!< Class code assigned by the USB - uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB - uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB - uint8_t iFunction; //!< Index of string descriptor + uint8_t bLength; //!< size of this descriptor in bytes + uint8_t bDescriptorType; //!< INTERFACE descriptor type + uint8_t bFirstInterface; //!< Number of interface + uint8_t bInterfaceCount; //!< value to select alternate setting + uint8_t bFunctionClass; //!< Class code assigned by the USB + uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB + uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB + uint8_t iFunction; //!< Index of string descriptor } usb_association_desc_t; - /** * \brief Standard USB configuration descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t wTotalLength; - uint8_t bNumInterfaces; - uint8_t bConfigurationValue; - uint8_t iConfiguration; - uint8_t bmAttributes; - uint8_t bMaxPower; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t wTotalLength; + uint8_t bNumInterfaces; + uint8_t bConfigurationValue; + uint8_t iConfiguration; + uint8_t bmAttributes; + uint8_t bMaxPower; } usb_conf_desc_t; - #define USB_CONFIG_ATTR_MUST_SET (1 << 7) //!< Must always be set #define USB_CONFIG_ATTR_BUS_POWERED (0 << 6) //!< Bus-powered #define USB_CONFIG_ATTR_SELF_POWERED (1 << 6) //!< Self-powered @@ -438,55 +435,54 @@ typedef struct { * \brief Standard USB association descriptor structure */ typedef struct { - uint8_t bLength; //!< Size of this descriptor in bytes - uint8_t bDescriptorType; //!< Interface descriptor type - uint8_t bFirstInterface; //!< Number of interface - uint8_t bInterfaceCount; //!< value to select alternate setting - uint8_t bFunctionClass; //!< Class code assigned by the USB - uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB - uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB - uint8_t iFunction; //!< Index of string descriptor + uint8_t bLength; //!< Size of this descriptor in bytes + uint8_t bDescriptorType; //!< Interface descriptor type + uint8_t bFirstInterface; //!< Number of interface + uint8_t bInterfaceCount; //!< value to select alternate setting + uint8_t bFunctionClass; //!< Class code assigned by the USB + uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB + uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB + uint8_t iFunction; //!< Index of string descriptor } usb_iad_desc_t; /** * \brief Standard USB interface descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bInterfaceNumber; - uint8_t bAlternateSetting; - uint8_t bNumEndpoints; - uint8_t bInterfaceClass; - uint8_t bInterfaceSubClass; - uint8_t bInterfaceProtocol; - uint8_t iInterface; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bInterfaceNumber; + uint8_t bAlternateSetting; + uint8_t bNumEndpoints; + uint8_t bInterfaceClass; + uint8_t bInterfaceSubClass; + uint8_t bInterfaceProtocol; + uint8_t iInterface; } usb_iface_desc_t; /** * \brief Standard USB endpoint descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bEndpointAddress; - uint8_t bmAttributes; - le16_t wMaxPacketSize; - uint8_t bInterval; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bEndpointAddress; + uint8_t bmAttributes; + le16_t wMaxPacketSize; + uint8_t bInterval; } usb_ep_desc_t; - /** * \brief A standard USB string descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; + uint8_t bLength; + uint8_t bDescriptorType; } usb_str_desc_t; typedef struct { - usb_str_desc_t desc; - le16_t string[1]; + usb_str_desc_t desc; + le16_t string[1]; } usb_str_lgid_desc_t; COMPILER_PACK_RESET() diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h index d594db52e3..769e7589bc 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h @@ -58,42 +58,42 @@ * \name Possible values of class */ //@{ -#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class -#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface -#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface +#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class +#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface +#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface #define CDC_CLASS_MULTI 0xEF //!< CDC Multi-interface Function //@} //! \name USB CDC Subclass IDs //@{ -#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model -#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model -#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model -#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model -#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model -#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model -#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model +#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model +#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model +#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model +#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model +#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model +#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model +#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model //@} //! \name USB CDC Communication Interface Protocol IDs //@{ -#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands +#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands //@} //! \name USB CDC Data Interface Protocol IDs //@{ -#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI -#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC -#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent -#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol -#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol -#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor -#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures -#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control -#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN -#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands -#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver +#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI +#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC +#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent +#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol +#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol +#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor +#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures +#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control +#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN +#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands +#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver /** * \brief Describes the Protocol Unit Functional Descriptors [sic] * on Communication Class Interface @@ -103,16 +103,16 @@ //! \name USB CDC Functional Descriptor Types //@{ -#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor -#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor +#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor +#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor //@} //! \name USB CDC Functional Descriptor Subtypes //@{ -#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor -#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management -#define CDC_SCS_ACM 0x02 //!< Abstract Control Management -#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor +#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor +#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management +#define CDC_SCS_ACM 0x02 //!< Abstract Control Management +#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor //@} //! \name USB CDC Request IDs @@ -168,42 +168,40 @@ COMPILER_PACK_SET(1) //! \name USB CDC Descriptors //@{ - //! CDC Header Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - le16_t bcdCDC; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + le16_t bcdCDC; } usb_cdc_hdr_desc_t; //! CDC Call Management Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bmCapabilities; - uint8_t bDataInterface; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bmCapabilities; + uint8_t bDataInterface; } usb_cdc_call_mgmt_desc_t; //! CDC ACM Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bmCapabilities; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bmCapabilities; } usb_cdc_acm_desc_t; //! CDC Union Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bMasterInterface; - uint8_t bSlaveInterface0; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bMasterInterface; + uint8_t bSlaveInterface0; } usb_cdc_union_desc_t; - //! \name USB CDC Call Management Capabilities //@{ //! Device handles call management itself @@ -235,24 +233,24 @@ typedef struct { //@{ //! Line Coding structure typedef struct { - le32_t dwDTERate; - uint8_t bCharFormat; - uint8_t bParityType; - uint8_t bDataBits; + le32_t dwDTERate; + uint8_t bCharFormat; + uint8_t bParityType; + uint8_t bDataBits; } usb_cdc_line_coding_t; //! Possible values of bCharFormat enum cdc_char_format { - CDC_STOP_BITS_1 = 0, //!< 1 stop bit - CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits - CDC_STOP_BITS_2 = 2, //!< 2 stop bits + CDC_STOP_BITS_1 = 0, //!< 1 stop bit + CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits + CDC_STOP_BITS_2 = 2, //!< 2 stop bits }; //! Possible values of bParityType enum cdc_parity { - CDC_PAR_NONE = 0, //!< No parity - CDC_PAR_ODD = 1, //!< Odd parity - CDC_PAR_EVEN = 2, //!< Even parity - CDC_PAR_MARK = 3, //!< Parity forced to 0 (space) - CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark) + CDC_PAR_NONE = 0, //!< No parity + CDC_PAR_ODD = 1, //!< Odd parity + CDC_PAR_EVEN = 2, //!< Even parity + CDC_PAR_MARK = 3, //!< Parity forced to 0 (space) + CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark) }; //@} @@ -262,7 +260,7 @@ enum cdc_parity { //! Control signal structure typedef struct { - uint16_t value; + uint16_t value; } usb_cdc_control_signal_t; //! \name Possible values in usb_cdc_control_signal_t @@ -278,16 +276,15 @@ typedef struct { //@} //@} - //! \name USB CDC notification message //@{ typedef struct { - uint8_t bmRequestType; - uint8_t bNotification; - le16_t wValue; - le16_t wIndex; - le16_t wLength; + uint8_t bmRequestType; + uint8_t bNotification; + le16_t wValue; + le16_t wIndex; + le16_t wLength; } usb_cdc_notify_msg_t; //! \name USB CDC serial state @@ -295,8 +292,8 @@ typedef struct { //! Hardware handshake support (cdc spec 1.1 chapter 6.3.5) typedef struct { - usb_cdc_notify_msg_t header; - le16_t value; + usb_cdc_notify_msg_t header; + le16_t value; } usb_cdc_notify_serial_state_t; //! \name Possible values in usb_cdc_notify_serial_state_t diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h index e1e59237d8..227a13dc53 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h @@ -47,7 +47,6 @@ #ifndef _USB_PROTOCOL_MSC_H_ #define _USB_PROTOCOL_MSC_H_ - /** * \ingroup usb_protocol_group * \defgroup usb_msc_protocol USB Mass Storage Class (MSC) protocol definitions @@ -59,7 +58,7 @@ * \name Possible Class value */ //@{ -#define MSC_CLASS 0x08 +#define MSC_CLASS 0x08 //@} /** @@ -71,12 +70,12 @@ * operating systems like Windows XP. */ //@{ -#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands -#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices -#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices -#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives -#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives -#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY +#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands +#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices +#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices +#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives +#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives +#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY //@} /** @@ -84,21 +83,19 @@ * \note Only the BULK protocol should be used in new designs. */ //@{ -#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt -#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion -#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only +#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt +#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion +#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only //@} - /** * \brief MSC USB requests (bRequest) */ enum usb_reqid_msc { - USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset - USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN + USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset + USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN }; - COMPILER_PACK_SET(1) /** @@ -106,38 +103,37 @@ COMPILER_PACK_SET(1) */ //@{ struct usb_msc_cbw { - le32_t dCBWSignature; //!< Must contain 'USBC' - le32_t dCBWTag; //!< Unique command ID - le32_t dCBWDataTransferLength; //!< Number of bytes to transfer - uint8_t bmCBWFlags; //!< Direction in bit 7 - uint8_t bCBWLUN; //!< Logical Unit Number - uint8_t bCBWCBLength; //!< Number of valid CDB bytes - uint8_t CDB[16]; //!< SCSI Command Descriptor Block + le32_t dCBWSignature; //!< Must contain 'USBC' + le32_t dCBWTag; //!< Unique command ID + le32_t dCBWDataTransferLength; //!< Number of bytes to transfer + uint8_t bmCBWFlags; //!< Direction in bit 7 + uint8_t bCBWLUN; //!< Logical Unit Number + uint8_t bCBWCBLength; //!< Number of valid CDB bytes + uint8_t CDB[16]; //!< SCSI Command Descriptor Block }; -#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value -#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host -#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device -#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN -#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength +#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value +#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host +#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device +#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN +#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength //@} - /** * \name A Command Status Wrapper (CSW). */ //@{ struct usb_msc_csw { - le32_t dCSWSignature; //!< Must contain 'USBS' - le32_t dCSWTag; //!< Same as dCBWTag - le32_t dCSWDataResidue; //!< Number of bytes not transferred - uint8_t bCSWStatus; //!< Status code + le32_t dCSWSignature; //!< Must contain 'USBS' + le32_t dCSWTag; //!< Same as dCBWTag + le32_t dCSWDataResidue; //!< Number of bytes not transferred + uint8_t bCSWStatus; //!< Status code }; -#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value -#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed -#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed -#define USB_CSW_STATUS_PE 0x02 //!< Phase Error +#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value +#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed +#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed +#define USB_CSW_STATUS_PE 0x02 //!< Phase Error //@} COMPILER_PACK_RESET() diff --git a/Marlin/src/HAL/DUE/usb/usb_task.c b/Marlin/src/HAL/DUE/usb/usb_task.c index 54a808d7f4..6f027f83a1 100644 --- a/Marlin/src/HAL/DUE/usb/usb_task.c +++ b/Marlin/src/HAL/DUE/usb/usb_task.c @@ -51,18 +51,18 @@ #include "conf_usb.h" #include "udc.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA static volatile bool main_b_msc_enable = false; #endif static volatile bool main_b_cdc_enable = false; static volatile bool main_b_dtr_active = false; void usb_task_idle(void) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA // Attend SD card access from the USB MSD -- Prioritize access to improve speed int delay = 2; while (main_b_msc_enable && --delay > 0) { - if (udi_msc_process_trans()) delay = 10000; + if (udi_msc_process_trans()) delay = 20; // Reset the watchdog, just to be sure REG_WDT_CR = WDT_CR_WDRSTT | WDT_CR_KEY(0xA5); @@ -70,7 +70,7 @@ void usb_task_idle(void) { #endif } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA bool usb_task_msc_enable(void) { return ((main_b_msc_enable = true)); } void usb_task_msc_disable(void) { main_b_msc_enable = false; } bool usb_task_msc_isenabled(void) { return main_b_msc_enable; } @@ -206,13 +206,13 @@ static USB_MicrosoftExtendedPropertiesDescriptor microsoft_extended_properties_d bool usb_task_extra_string(void) { static uint8_t udi_msft_magic[] = "MSFT100\xEE"; static uint8_t udi_cdc_name[] = "CDC interface"; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static uint8_t udi_msc_name[] = "MSC interface"; #endif struct extra_strings_desc_t { usb_str_desc_t header; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA le16_t string[Max(Max(sizeof(udi_cdc_name) - 1, sizeof(udi_msc_name) - 1), sizeof(udi_msft_magic) - 1)]; #else le16_t string[Max(sizeof(udi_cdc_name) - 1, sizeof(udi_msft_magic) - 1)]; @@ -231,7 +231,7 @@ bool usb_task_extra_string(void) { str_lgt = sizeof(udi_cdc_name) - 1; str = udi_cdc_name; break; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case UDI_MSC_STRING_ID: str_lgt = sizeof(udi_msc_name) - 1; str = udi_msc_name; diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 29f3be3c02..acfec29b2f 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -34,13 +34,13 @@ #if ENABLED(WIFISUPPORT) #include - #include "wifi.h" + #include "wifi/wifi.h" #if ENABLED(OTASUPPORT) - #include "ota.h" + #include "wifi/ota.h" #endif #if ENABLED(WEBSUPPORT) - #include "spiffs.h" - #include "web.h" + #include "wifi/spiffs.h" + #include "wifi/web.h" #endif #endif @@ -165,7 +165,7 @@ void MarlinHAL::init_board() { } void MarlinHAL::idletask() { - #if BOTH(WIFISUPPORT, OTASUPPORT) + #if ALL(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); @@ -175,8 +175,6 @@ uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); } void MarlinHAL::reboot() { ESP.restart(); } -void _delay_ms(int delay_ms) { delay(delay_ms); } - // return free memory between end of heap (or end bss) and whatever is current int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } @@ -209,16 +207,17 @@ int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } // ADC // ------------------------ -#define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL - +// https://docs.espressif.com/projects/esp-idf/en/release-v4.4/esp32/api-reference/peripherals/adc.html adc1_channel_t get_channel(int pin) { switch (pin) { - case 39: return ADC1_CHANNEL(39); - case 36: return ADC1_CHANNEL(36); - case 35: return ADC1_CHANNEL(35); - case 34: return ADC1_CHANNEL(34); - case 33: return ADC1_CHANNEL(33); - case 32: return ADC1_CHANNEL(32); + case 39: return ADC1_CHANNEL_3; + case 36: return ADC1_CHANNEL_0; + case 35: return ADC1_CHANNEL_7; + case 34: return ADC1_CHANNEL_6; + case 33: return ADC1_CHANNEL_5; + case 32: return ADC1_CHANNEL_4; + case 37: return ADC1_CHANNEL_1; + case 38: return ADC1_CHANNEL_2; } return ADC1_CHANNEL_MAX; } @@ -243,12 +242,13 @@ void MarlinHAL::adc_init() { TERN_(HAS_TEMP_ADC_5, adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db)); TERN_(HAS_TEMP_ADC_6, adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db)); TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db)); - TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db)); - TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db)); - TERN_(HAS_TEMP_PROBE, adc1_set_attenuation(get_channel(TEMP_PROBE_PIN), ADC_ATTEN_11db)); - TERN_(HAS_TEMP_COOLER, adc1_set_attenuation(get_channel(TEMP_COOLER_PIN), ADC_ATTEN_11db)); - TERN_(HAS_TEMP_BOARD, adc1_set_attenuation(get_channel(TEMP_BOARD_PIN), ADC_ATTEN_11db)); - TERN_(FILAMENT_WIDTH_SENSOR, adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_PROBE, adc1_set_attenuation(get_channel(TEMP_PROBE_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_COOLER, adc1_set_attenuation(get_channel(TEMP_COOLER_PIN), ADC_ATTEN_11db)); + TERN_(HAS_TEMP_ADC_BOARD, adc1_set_attenuation(get_channel(TEMP_BOARD_PIN), ADC_ATTEN_11db)); + TERN_(HAS_FILWIDTH_ADC, adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db)); + TERN_(HAS_FILWIDTH2_ADC, adc1_set_attenuation(get_channel(FILWIDTH2_PIN), ADC_ATTEN_11db)); // Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail. // That's why we're not setting it up here. @@ -271,7 +271,7 @@ void MarlinHAL::adc_start(const pin_t pin) { uint32_t mv; esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv); - adc_result = mv * isr_float_t(1023) / isr_float_t(ADC_REFERENCE_VOLTAGE) / isr_float_t(1000); + adc_result = (mv * 1023) * (1000.f / (ADC_REFERENCE_VOLTAGE)); // Change the attenuation level based on the new reading adc_atten_t atten; @@ -342,16 +342,16 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v } else pindata.pwm_duty_ticks = duty; // PWM duty count = # of 4µs ticks per full PWM cycle + + return; } - 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); - } - } + + 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) { @@ -360,17 +360,15 @@ int8_t MarlinHAL::set_pwm_frequency(const pin_t pin, const uint32_t f_desired) { 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 - } + + 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 ddfedf92ee..f48eabea0d 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -35,11 +37,11 @@ #include "i2s.h" #if ENABLED(WIFISUPPORT) - #include "WebSocketSerial.h" + #include "wifi/WebSocketSerial.h" #endif #if ENABLED(ESP3D_WIFISUPPORT) - #include "esp3dlib.h" + #include #endif #include "FlushableHardwareSerial.h" @@ -50,24 +52,22 @@ #define MYSERIAL1 flushableSerial -#if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) - #if ENABLED(ESP3D_WIFISUPPORT) - typedef ForwardSerial1Class< decltype(Serial2Socket) > DefaultSerial1; - extern DefaultSerial1 MSerial0; - #define MYSERIAL2 MSerial0 - #else - #define MYSERIAL2 webSocketSerial - #endif +#if ENABLED(ESP3D_WIFISUPPORT) + typedef ForwardSerial1Class< decltype(Serial2Socket) > DefaultSerial1; + extern DefaultSerial1 MSerial0; + #define MYSERIAL2 MSerial0 +#elif ENABLED(WIFISUPPORT) + #define MYSERIAL2 webSocketSerial #endif #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 +#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 @@ -76,7 +76,6 @@ // Types // ------------------------ -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 { @@ -165,13 +164,11 @@ int freeMemory(); #pragma GCC diagnostic pop -void _delay_ms(const int ms); - // ------------------------ // MarlinHAL Class // ------------------------ -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 class MarlinHAL { @@ -194,9 +191,9 @@ public: static void isr_on() { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); } static void isr_off() { portENTER_CRITICAL(&spinlock); } - static void delay_ms(const int ms) { _delay_ms(ms); } + static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 868ab1b671..e5302bb905 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -53,7 +52,7 @@ static SPISettings spiConfig; // ------------------------ void spiBegin() { - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_SS) + #if HAS_MEDIA && PIN_EXISTS(SD_SS) OUT_WRITE(SD_SS_PIN, HIGH); #endif } diff --git a/Marlin/src/HAL/ESP32/Servo.cpp b/Marlin/src/HAL/ESP32/Servo.cpp index ca3950d07f..3a2c11832d 100644 --- a/Marlin/src/HAL/ESP32/Servo.cpp +++ b/Marlin/src/HAL/ESP32/Servo.cpp @@ -35,7 +35,7 @@ Servo::Servo() {} int8_t Servo::attach(const int inPin) { if (inPin > 0) pin = inPin; - channel = get_pwm_channel(pin, 50u, 16u); + channel = get_pwm_channel(pin, 50U, 16U); return channel; // -1 if no PWM avail. } diff --git a/Marlin/src/HAL/ESP32/Tone.cpp b/Marlin/src/HAL/ESP32/Tone.cpp index 839c612b6a..1bb0840129 100644 --- a/Marlin/src/HAL/ESP32/Tone.cpp +++ b/Marlin/src/HAL/ESP32/Tone.cpp @@ -24,7 +24,7 @@ /** * Description: Tone function for ESP32 - * Derived from https://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012 + * Derived from https://forum.arduino.cc/t/arduino-due-and-tone/133302/13 */ #ifdef ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/eeprom.cpp b/Marlin/src/HAL/ESP32/eeprom.cpp index cb5f881284..ca4a806361 100644 --- a/Marlin/src/HAL/ESP32/eeprom.cpp +++ b/Marlin/src/HAL/ESP32/eeprom.cpp @@ -31,24 +31,28 @@ #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { return EEPROM.begin(MARLIN_EEPROM_SIZE); } bool PersistentStore::access_finish() { EEPROM.end(); return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { for (size_t i = 0; i < size; i++) { - EEPROM.write(pos++, value[i]); + const int p = REAL_EEPROM_ADDR(pos); + EEPROM.write(p, value[i]); crc16(crc, &value[i], 1); + ++pos; } return false; } bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { for (size_t i = 0; i < size; i++) { - uint8_t c = EEPROM.read(pos++); + const int p = REAL_EEPROM_ADDR(pos); + uint8_t c = EEPROM.read(p); if (writing) value[i] = c; crc16(crc, &c, 1); + ++pos; } return false; } diff --git a/Marlin/src/HAL/ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h index 0536864610..8b88f1f41f 100644 --- a/Marlin/src/HAL/ESP32/endstop_interrupts.h +++ b/Marlin/src/HAL/ESP32/endstop_interrupts.h @@ -42,33 +42,34 @@ void ICACHE_RAM_ATTR endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); - TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h index c8e3f7e343..a85423d768 100644 --- a/Marlin/src/HAL/ESP32/fastio.h +++ b/Marlin/src/HAL/ESP32/fastio.h @@ -37,6 +37,10 @@ // Set pin as output #define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) +// TODO: Store set modes in an array and use those to get the mode +#define _IS_OUTPUT(IO) true +#define _IS_INPUT(IO) true + // Set pin as input with pullup mode #define _PULLUP(IO, v) pinMode(IO, v ? INPUT_PULLUP : INPUT) @@ -70,6 +74,9 @@ // Set pin as output and init #define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) +#define IS_OUTPUT(IO) _IS_OUTPUT(IO) +#define IS_INPUT(IO) _IS_INPUT(IO) + // digitalRead/Write wrappers #define extDigitalRead(IO) digitalRead(IO) #define extDigitalWrite(IO,V) digitalWrite(IO,V) diff --git a/Marlin/src/HAL/ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp index cf337eeb46..f7c01730b3 100644 --- a/Marlin/src/HAL/ESP32/i2s.cpp +++ b/Marlin/src/HAL/ESP32/i2s.cpp @@ -34,6 +34,10 @@ #include #include "../../module/stepper.h" +#if ENABLED(FT_MOTION) + #include "../../module/ft_motion.h" +#endif + #define DMA_BUF_COUNT 8 // number of DMA buffers to store data #define DMA_BUF_LEN 4092 // maximum size in bytes #define I2S_SAMPLE_SIZE 4 // 4 bytes, 32 bits per sample @@ -134,26 +138,61 @@ static void IRAM_ATTR i2s_intr_handler_default(void *arg) { if (high_priority_task_awoken == pdTRUE) portYIELD_FROM_ISR(); - // clear interrupt - I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt + // Clear pending interrupt + I2S0.int_clr.val = I2S0.int_st.val; } void stepperTask(void *parameter) { - uint32_t remaining = 0; + uint32_t nextMainISR = 0; + #if ENABLED(LIN_ADVANCE) + uint32_t nextAdvanceISR = stepper.LA_ADV_NEVER; + #endif - while (1) { + for (;;) { xQueueReceive(dma.queue, &dma.current, portMAX_DELAY); dma.rw_pos = 0; + const bool using_ftMotion = TERN0(FT_MOTION, ftMotion.cfg.active); + while (dma.rw_pos < DMA_SAMPLE_COUNT) { - // Fill with the port data post pulse_phase until the next step - if (remaining) { - i2s_push_sample(); - remaining--; + + if (using_ftMotion) { + + #if ENABLED(FT_MOTION) + if (!nextMainISR) stepper.ftMotion_stepper(); + nextMainISR = 0; + #endif + } else { - Stepper::pulse_phase_isr(); - remaining = Stepper::block_phase_isr(); + + #if HAS_STANDARD_MOTION + + if (!nextMainISR) { + stepper.pulse_phase_isr(); + nextMainISR = stepper.block_phase_isr(); + } + #if ENABLED(LIN_ADVANCE) + else if (!nextAdvanceISR) { + stepper.advance_isr(); + nextAdvanceISR = stepper.la_interval; + } + #endif + else + i2s_push_sample(); + + nextMainISR--; + + #if ENABLED(LIN_ADVANCE) + if (nextAdvanceISR == stepper.LA_ADV_NEVER) + nextAdvanceISR = stepper.la_interval; + + if (nextAdvanceISR && nextAdvanceISR != stepper.LA_ADV_NEVER) + nextAdvanceISR--; + #endif + + #endif // HAS_STANDARD_MOTION + } } } @@ -340,7 +379,7 @@ void i2s_push_sample() { // Every 4µs (when space in DMA buffer) toggle each expander PWM output using // the current duty cycle/frequency so they sync with any steps (once // through the DMA/FIFO buffers). PWM signal inversion handled by other functions - LOOP_L_N(p, MAX_EXPANDER_BITS) { + for (uint8_t p = 0; p < MAX_EXPANDER_BITS; ++p) { if (hal.pwm_pin_data[p].pwm_duty_ticks > 0) { // pin has active pwm? if (hal.pwm_pin_data[p].pwm_tick_count == 0) { if (TEST32(i2s_port_data, p)) { // hi->lo diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h b/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h index 4da600179d..07d2efe0bd 100644 --- a/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/ESP32." +#if ANY(MKS_MINI_12864, FYSETC_MINI_12864_2_1) + #define U8G_HW_SPI_ESP32 1 #endif diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_type.h b/Marlin/src/HAL/ESP32/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h index 3ccb15989f..dd199c390d 100644 --- a/Marlin/src/HAL/ESP32/inc/SanityCheck.h +++ b/Marlin/src/HAL/ESP32/inc/SanityCheck.h @@ -21,19 +21,26 @@ */ #pragma once +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for HAL/ESP32." +#endif + #if ENABLED(EMERGENCY_PARSER) #error "EMERGENCY_PARSER is not yet implemented for ESP32. Disable EMERGENCY_PARSER to continue." #endif -#if (ENABLED(SPINDLE_LASER_USE_PWM) && SPINDLE_LASER_FREQUENCY > 78125) || (ENABLED(FAST_PWM_FAN_FREQUENCY) && FAST_PWM_FAN_FREQUENCY > 78125) - #error "SPINDLE_LASER_FREQUENCY and FAST_PWM_FREQUENCY maximum value is 78125Hz for ESP32." +#if ENABLED(SPINDLE_LASER_USE_PWM) && SPINDLE_LASER_FREQUENCY > 78125 + #error "SPINDLE_LASER_FREQUENCY maximum value is 78125Hz for ESP32." +#endif +#if ENABLED(FAST_PWM_FAN) && FAST_PWM_FAN_FREQUENCY > 78125 + #error "FAST_PWM_FREQUENCY maximum value is 78125Hz for ESP32." #endif #if HAS_TMC_SW_SERIAL #error "TMC220x Software Serial is not supported on ESP32." #endif -#if BOTH(WIFISUPPORT, ESP3D_WIFISUPPORT) +#if ALL(WIFISUPPORT, ESP3D_WIFISUPPORT) #error "Only enable one WiFi option, either WIFISUPPORT or ESP3D_WIFISUPPORT." #endif @@ -49,6 +56,10 @@ #error "PULLDOWN pin mode is not available on ESP32 boards." #endif -#if BOTH(I2S_STEPPER_STREAM, LIN_ADVANCE) +#if ALL(I2S_STEPPER_STREAM, LIN_ADVANCE) && DISABLED(EXPERIMENTAL_I2S_LA) #error "I2S stream is currently incompatible with LIN_ADVANCE." #endif + +#if ALL(I2S_STEPPER_STREAM, PRINTCOUNTER) && PRINTCOUNTER_SAVE_INTERVAL > 0 && DISABLED(PRINTCOUNTER_SYNC) + #error "PRINTCOUNTER_SAVE_INTERVAL may cause issues on ESP32 with an I2S expander. Define PRINTCOUNTER_SYNC in Configuration.h for an imperfect solution." +#endif diff --git a/Marlin/src/HAL/ESP32/pinsDebug.h b/Marlin/src/HAL/ESP32/pinsDebug.h new file mode 100644 index 0000000000..42304b2a0b --- /dev/null +++ b/Marlin/src/HAL/ESP32/pinsDebug.h @@ -0,0 +1,71 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +#error "PINS_DEBUGGING is not yet supported for ESP32!" + +/** + * Pins Debugging for ESP32 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS +#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin + +#define digitalRead_mod(P) extDigitalRead(P) +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define getPinByIndex(x) pin_array[x].pin +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL)) +#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0)) +#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1))) +bool pwm_status(const pin_t) { return false; } + +void printPinPort(const pin_t) {} + +static bool getValidPinMode(const pin_t pin) { + return isValidPin(pin) && !IS_INPUT(pin); +} + +void printPinPWM(const int32_t pin) { + if (pwm_status(pin)) { + //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative; + //SERIAL_ECHOPGM("PWM = ", duty); + } +} diff --git a/Marlin/src/HAL/ESP32/spi_pins.h b/Marlin/src/HAL/ESP32/spi_pins.h index 58881f0ea7..b50ea725ab 100644 --- a/Marlin/src/HAL/ESP32/spi_pins.h +++ b/Marlin/src/HAL/ESP32/spi_pins.h @@ -21,7 +21,16 @@ */ #pragma once -#define SD_SS_PIN SDSS -#define SD_SCK_PIN 18 -#define SD_MISO_PIN 19 -#define SD_MOSI_PIN 23 +#define PIN_SPI_SCK 18 +#define PIN_SPI_MISO 19 +#define PIN_SPI_MOSI 23 + +#ifndef SD_SCK_PIN + #define SD_SCK_PIN PIN_SPI_SCK +#endif +#ifndef SD_MISO_PIN + #define SD_MISO_PIN PIN_SPI_MISO +#endif +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN PIN_SPI_MOSI +#endif diff --git a/Marlin/src/HAL/ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp index c37ad2430c..a2996a860f 100644 --- a/Marlin/src/HAL/ESP32/timers.cpp +++ b/Marlin/src/HAL/ESP32/timers.cpp @@ -78,8 +78,8 @@ void IRAM_ATTR timer_isr(void *para) { /** * Enable and initialize the timer - * @param timer_num timer number to initialize - * @param frequency frequency of the timer + * @param timer_num timer number to initialize + * @param frequency frequency of the timer */ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { const tTimerConfig timer = timer_config[timer_num]; @@ -90,7 +90,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { config.counter_en = TIMER_PAUSE; config.alarm_en = TIMER_ALARM_EN; config.intr_type = TIMER_INTR_LEVEL; - config.auto_reload = true; + config.auto_reload = TIMER_AUTORELOAD_EN; // Select and initialize the timer timer_init(timer.group, timer.idx, &config); @@ -111,12 +111,12 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { /** * Set the upper value of the timer, when the timer reaches this upper value the * interrupt should be triggered and the counter reset - * @param timer_num timer number to set the count to - * @param count threshold at which the interrupt is triggered + * @param timer_num timer number to set the compare value to + * @param compare threshold at which the interrupt is triggered */ -void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t count) { +void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { const tTimerConfig timer = timer_config[timer_num]; - timer_set_alarm_value(timer.group, timer.idx, count); + timer_set_alarm_value(timer.group, timer.idx, compare); } /** diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index aa4e1551f0..d656e92224 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -30,42 +30,45 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint64_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX) #ifndef MF_TIMER_STEP #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif #ifndef MF_TIMER_PULSE - #define MF_TIMER_PULSE MF_TIMER_STEP + #define MF_TIMER_PULSE MF_TIMER_STEP // Timer Index for Pulse interval #endif #ifndef MF_TIMER_TEMP #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif #ifndef MF_TIMER_PWM - #define MF_TIMER_PWM 2 // index of timer to use for PWM outputs + #define MF_TIMER_PWM 2 // Timer Index for PWM outputs #endif #ifndef MF_TIMER_TONE - #define MF_TIMER_TONE 3 // index of timer for beeper tones + #define MF_TIMER_TONE 3 // Timer Index for beeper tones #endif -#define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals +#define HAL_TIMER_RATE APB_CLK_FREQ // Frequency of timer peripherals + +#define TEMP_TIMER_PRESCALE 1000 // Prescaler for setting Temp Timer, 72Khz +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency #if ENABLED(I2S_STEPPER_STREAM) #define STEPPER_TIMER_PRESCALE 1 - #define STEPPER_TIMER_RATE 250000 // 250khz, 4µs pulses of i2s word clock - #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs // wrong would be 0.25 + #define STEPPER_TIMER_RATE 250'000 // 250khz, 4µs pulses of i2s word clock + #define STEPPER_TIMER_TICKS_PER_US 0.25 // (MHz) Stepper Timer ticks per µs #else #define STEPPER_TIMER_PRESCALE 40 - #define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz - #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs + #define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // (Hz) Frequency of Stepper Timer ISR, 2MHz + #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000UL) // (MHz) Stepper Timer ticks per µs #endif #define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts -#define TONE_TIMER_PRESCALE 1000 // Arbitrary value, no idea what i'm doing here +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TONE_TIMER_PRESCALE 1000 // Arbitrary value, no idea what i'm doing here #define PWM_TIMER_PRESCALE 10 #if ENABLED(FAST_PWM_FAN) @@ -75,13 +78,9 @@ typedef uint64_t hal_timer_t; #endif #define MAX_PWM_PINS 32 // Number of PWM pin-slots -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US - -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) #define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) @@ -136,5 +135,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/ESP32/u8g/LCD_defines.h b/Marlin/src/HAL/ESP32/u8g/LCD_defines.h new file mode 100644 index 0000000000..3696d60d7c --- /dev/null +++ b/Marlin/src/HAL/ESP32/u8g/LCD_defines.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * ESP32 LCD-specific defines + */ + +uint8_t u8g_esp32_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); +#define U8G_COM_HAL_HW_SPI_FN u8g_esp32_hw_spi_fn diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index a445035b2b..42903da9d3 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -25,15 +25,21 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1) +#if U8G_HW_SPI_ESP32 #include #include "../shared/HAL_SPI.h" #include "HAL.h" #include "SPI.h" -static SPISettings spiConfig; +#if HAS_MEDIA + #include "../../sd/cardreader.h" + #if ENABLED(ESP3D_WIFISUPPORT) + #include + #endif +#endif +static SPISettings spiConfig; #ifndef LCD_SPI_SPEED #ifdef SD_SPI_SPEED @@ -43,8 +49,13 @@ static SPISettings spiConfig; #endif #endif -uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { +uint8_t u8g_esp32_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { static uint8_t msgInitCount = 2; // Ignore all messages until 2nd U8G_COM_MSG_INIT + + #if ENABLED(PAUSE_LCD_FOR_BUSY_SD) + if (card.flag.saving || card.flag.logging || TERN0(ESP3D_WIFISUPPORT, sd_busy_lock == true)) return 0; + #endif + if (msgInitCount) { if (msg == U8G_COM_MSG_INIT) msgInitCount--; if (msgInitCount) return -1; @@ -89,6 +100,5 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt return 1; } -#endif // EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1) - +#endif // U8G_HW_SPI_ESP32 #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp b/Marlin/src/HAL/ESP32/wifi/WebSocketSerial.cpp similarity index 99% rename from Marlin/src/HAL/ESP32/WebSocketSerial.cpp rename to Marlin/src/HAL/ESP32/wifi/WebSocketSerial.cpp index eb5b9d6039..9c8933289d 100644 --- a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp +++ b/Marlin/src/HAL/ESP32/wifi/WebSocketSerial.cpp @@ -21,7 +21,7 @@ */ #ifdef ARDUINO_ARCH_ESP32 -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(WIFISUPPORT) diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.h b/Marlin/src/HAL/ESP32/wifi/WebSocketSerial.h similarity index 96% rename from Marlin/src/HAL/ESP32/WebSocketSerial.h rename to Marlin/src/HAL/ESP32/wifi/WebSocketSerial.h index 6b3e419d10..3d2fdf1e6a 100644 --- a/Marlin/src/HAL/ESP32/WebSocketSerial.h +++ b/Marlin/src/HAL/ESP32/wifi/WebSocketSerial.h @@ -21,8 +21,8 @@ */ #pragma once -#include "../../inc/MarlinConfig.h" -#include "../../core/serial_hook.h" +#include "../../../inc/MarlinConfig.h" +#include "../../../core/serial_hook.h" #include diff --git a/Marlin/src/HAL/ESP32/ota.cpp b/Marlin/src/HAL/ESP32/wifi/ota.cpp similarity index 90% rename from Marlin/src/HAL/ESP32/ota.cpp rename to Marlin/src/HAL/ESP32/wifi/ota.cpp index 69a3e25e56..03508840a5 100644 --- a/Marlin/src/HAL/ESP32/ota.cpp +++ b/Marlin/src/HAL/ESP32/wifi/ota.cpp @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,11 +22,15 @@ #ifdef ARDUINO_ARCH_ESP32 -#include "../../inc/MarlinConfigPre.h" - -#if BOTH(WIFISUPPORT, OTASUPPORT) - #include + +#undef ENABLED +#undef DISABLED + +#include "../../../inc/MarlinConfigPre.h" + +#if ALL(WIFISUPPORT, OTASUPPORT) + #include #include #include @@ -50,7 +56,7 @@ void OTA_init() { }) .onError([](ota_error_t error) { Serial.printf("Error[%u]: ", error); - char *str; + const char *str = "unknown"; switch (error) { case OTA_AUTH_ERROR: str = "Auth Failed"; break; case OTA_BEGIN_ERROR: str = "Begin Failed"; break; diff --git a/Marlin/src/HAL/ESP32/ota.h b/Marlin/src/HAL/ESP32/wifi/ota.h similarity index 90% rename from Marlin/src/HAL/ESP32/ota.h rename to Marlin/src/HAL/ESP32/wifi/ota.h index 546ace82db..a91d04dbb7 100644 --- a/Marlin/src/HAL/ESP32/ota.h +++ b/Marlin/src/HAL/ESP32/wifi/ota.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/ESP32/spiffs.cpp b/Marlin/src/HAL/ESP32/wifi/spiffs.cpp similarity index 91% rename from Marlin/src/HAL/ESP32/spiffs.cpp rename to Marlin/src/HAL/ESP32/wifi/spiffs.cpp index a0e713bff0..ba891acda9 100644 --- a/Marlin/src/HAL/ESP32/spiffs.cpp +++ b/Marlin/src/HAL/ESP32/wifi/spiffs.cpp @@ -21,11 +21,11 @@ */ #ifdef ARDUINO_ARCH_ESP32 -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" -#if BOTH(WIFISUPPORT, WEBSUPPORT) +#if ALL(WIFISUPPORT, WEBSUPPORT) -#include "../../core/serial.h" +#include "../../../core/serial.h" #include #include diff --git a/Marlin/src/HAL/ESP32/spiffs.h b/Marlin/src/HAL/ESP32/wifi/spiffs.h similarity index 100% rename from Marlin/src/HAL/ESP32/spiffs.h rename to Marlin/src/HAL/ESP32/wifi/spiffs.h diff --git a/Marlin/src/HAL/ESP32/web.cpp b/Marlin/src/HAL/ESP32/wifi/web.cpp similarity index 92% rename from Marlin/src/HAL/ESP32/web.cpp rename to Marlin/src/HAL/ESP32/wifi/web.cpp index 7a27707a3e..f08dfd87c0 100644 --- a/Marlin/src/HAL/ESP32/web.cpp +++ b/Marlin/src/HAL/ESP32/wifi/web.cpp @@ -21,11 +21,11 @@ */ #ifdef ARDUINO_ARCH_ESP32 -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" -#if BOTH(WIFISUPPORT, WEBSUPPORT) +#if ALL(WIFISUPPORT, WEBSUPPORT) -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #undef DISABLED // esp32-hal-gpio.h #include diff --git a/Marlin/src/HAL/ESP32/web.h b/Marlin/src/HAL/ESP32/wifi/web.h similarity index 100% rename from Marlin/src/HAL/ESP32/web.h rename to Marlin/src/HAL/ESP32/wifi/web.h diff --git a/Marlin/src/HAL/ESP32/wifi.cpp b/Marlin/src/HAL/ESP32/wifi/wifi.cpp similarity index 96% rename from Marlin/src/HAL/ESP32/wifi.cpp rename to Marlin/src/HAL/ESP32/wifi/wifi.cpp index 060f3bdb48..1f31ca1bb9 100644 --- a/Marlin/src/HAL/ESP32/wifi.cpp +++ b/Marlin/src/HAL/ESP32/wifi/wifi.cpp @@ -21,11 +21,12 @@ */ #ifdef ARDUINO_ARCH_ESP32 -#include "../../core/serial.h" -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(WIFISUPPORT) +#include "../../../core/serial.h" + #include #include #include diff --git a/Marlin/src/HAL/ESP32/wifi.h b/Marlin/src/HAL/ESP32/wifi/wifi.h similarity index 100% rename from Marlin/src/HAL/ESP32/wifi.h rename to Marlin/src/HAL/ESP32/wifi/wifi.h diff --git a/Marlin/src/HAL/GD32_MFL/HAL.cpp b/Marlin/src/HAL/GD32_MFL/HAL.cpp new file mode 100644 index 0000000000..9ba20784f0 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/HAL.cpp @@ -0,0 +1,123 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ARDUINO_ARCH_MFL + +#include "../../inc/MarlinConfig.h" +#include "../shared/Delay.h" + +uint16_t MarlinHAL::adc_result; + +#if ENABLED(POSTMORTEM_DEBUGGING) + extern void install_min_serial(); +#endif + +#if ENABLED(MARLIN_DEV_MODE) + // Dump the clock frequencies of the system, AHB, APB1, APB2, and F_CPU. + static inline void HAL_clock_frequencies_dump() { + auto& rcuInstance = rcu::RCU::get_instance(); + uint32_t freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_SYS); + SERIAL_ECHOPGM("\nSYSTEM_CLOCK=", freq); + freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_AHB); + SERIAL_ECHOPGM("\nABH_CLOCK=", freq); + freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_APB1); + SERIAL_ECHOPGM("\nAPB1_CLOCK=", freq); + freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_APB2); + SERIAL_ECHOPGM("\nAPB2_CLOCK=", freq, + "\nF_CPU=", F_CPU); + // Done + SERIAL_ECHOPGM("\n--\n"); + } +#endif // MARLIN_DEV_MODE + +// Initializes the Marlin HAL +void MarlinHAL::init() { + // Ensure F_CPU is a constant expression. + // If the compiler breaks here, it means that delay code that should compute at compile time will not work. + // So better safe than sorry here. + constexpr unsigned int cpuFreq = F_CPU; + UNUSED(cpuFreq); + + #if PIN_EXISTS(LED) + OUT_WRITE(LED_PIN, LOW); + #endif + + SetTimerInterruptPriorities(); + + // Print clock frequencies to host serial + TERN_(MARLIN_DEV_MODE, HAL_clock_frequencies_dump()); + + // Register min serial + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); +} + +// Returns the reset source based on the flags set in the RCU module +uint8_t MarlinHAL::get_reset_source() { + return + (RCU_I.get_flag(rcu::Status_Flags::FLAG_FWDGTRST)) ? RST_WATCHDOG : + (RCU_I.get_flag(rcu::Status_Flags::FLAG_SWRST)) ? RST_SOFTWARE : + (RCU_I.get_flag(rcu::Status_Flags::FLAG_EPRST)) ? RST_EXTERNAL : + (RCU_I.get_flag(rcu::Status_Flags::FLAG_PORRST)) ? RST_POWER_ON : + (RCU_I.get_flag(rcu::Status_Flags::FLAG_LPRST)) ? RST_BROWN_OUT : + 0; +} + +// Returns the amount of free memory available in bytes +int MarlinHAL::freeMemory() { + volatile char top; + return &top - reinterpret_cast(_sbrk(0)); +} + +// Watchdog Timer +#if ENABLED(USE_WATCHDOG) + #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + + #include + + FWatchdogTimer& watchdogTimer = FWatchdogTimer::get_instance(); + + // Initializes the watchdog timer + void MarlinHAL::watchdog_init() { + IF_DISABLED(DISABLE_WATCHDOG_INIT, watchdogTimer.begin(WDT_TIMEOUT_US)); + } + + // Refreshes the watchdog timer to prevent system reset + void MarlinHAL::watchdog_refresh() { + watchdogTimer.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 +} + +// Resets the system to initiate a firmware flash. +WEAK void flashFirmware(const int16_t) { + hal.reboot(); +} + +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/HAL.h b/Marlin/src/HAL/GD32_MFL/HAL.h new file mode 100644 index 0000000000..6195212028 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/HAL.h @@ -0,0 +1,159 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define CPU_32_BIT + +#include "../../core/macros.h" +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" + +#include "temp_soc.h" +#include "fastio.h" +#include "Servo.h" + +#include "../../inc/MarlinConfigPre.h" + +#include +#include +#include + +// Default graphical display delays +#define CPU_ST7920_DELAY_1 300 +#define CPU_ST7920_DELAY_2 40 +#define CPU_ST7920_DELAY_3 340 + +// Serial Ports +#include "MarlinSerial.h" + +// Interrupts +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() + +#define cli() __disable_irq() +#define sei() __enable_irq() + +// Alias of __bss_end__ +#define __bss_end __bss_end__ + +// Types +typedef uint8_t pin_t; // Parity with mfl platform + +// Servo +class libServo; +typedef libServo hal_servo_t; +#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() +#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() + +// Debugging +#define JTAG_DISABLE() AFIO_I.set_remap(gpio::Pin_Remap_Select::SWJ_DP_ONLY_REMAP) +#define JTAGSWD_DISABLE() AFIO_I.set_remap(gpio::Pin_Remap_Select::SWJ_ALL_DISABLED_REMAP) +#define JTAGSWD_RESET() AFIO_I.set_remap(gpio::Pin_Remap_Select::FULL_SWJ_REMAP) + +// ADC +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif + +#define HAL_ADC_VREF_MV 3300 + +// Disable Marlin's software oversampling. +// The MFL framework uses 16x hardware oversampling by default +#ifdef GD32F303RE + #define HAL_ADC_FILTERED +#endif + +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif + +void flashFirmware(const int16_t); + +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + +extern "C" char* _sbrk(int incr); +extern "C" char* dtostrf(double val, signed char width, unsigned char prec, char* sout); + +// MarlinHAL Class +class MarlinHAL { +public: + // Before setup() + MarlinHAL() = default; + + // 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() { NVIC_SystemReset(); } // restart the firmware from 0x0 + + // Interrupts + static bool isr_state() { return !__get_PRIMASK(); } + static void isr_on() { sei(); } + static void isr_off() { cli(); } + static void delay_ms(const int ms) { delay(ms); } + + // Tasks called from idle() + static void idletask() {} + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source() { RCU_I.clear_all_reset_flags(); } + + // Free SRAM + static int freeMemory(); + + // ADC methods + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); } + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin) { pinMode(pin, INPUT); } + + // Called from Temperature::isr to start ADC sampling on the given pin + static void adc_start(const pin_t pin) { adc_result = static_cast(analogRead(pin)); } + + // Check if ADC is ready for reading + static bool adc_ready() { return true; } + + // Current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + // Set the PWM duty cycle for the pin to the given value. + // Optionally invert the duty cycle [default = false] + // Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + static void set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale = 255U, const bool invert = false); + + // Set the frequency of the timer for the given pin. + // All Timer PWM pins run at the same frequency. + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); +}; diff --git a/Marlin/src/HAL/GD32_MFL/MarlinSPI.h b/Marlin/src/HAL/GD32_MFL/MarlinSPI.h new file mode 100644 index 0000000000..d0731f9e84 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp b/Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp new file mode 100644 index 0000000000..95ea8bea25 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp @@ -0,0 +1,97 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ARDUINO_ARCH_MFL + +#include "../../inc/MarlinConfig.h" +#include "MarlinSerial.h" + +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif + +using namespace arduino; + +auto MarlinSerial::get_instance(usart::USART_Base Base, pin_size_t rxPin, pin_size_t txPin) -> MarlinSerial& { + auto& serial = UsartSerial::get_instance(Base, rxPin, txPin); + return *reinterpret_cast(&serial); +} + +#if USING_HW_SERIAL0 + MSerialT MSerial0(true, MarlinSerial::get_instance(usart::USART_Base::USART0_BASE, NO_PIN, NO_PIN)); +#endif +#if USING_HW_SERIAL1 + MSerialT MSerial1(true, MarlinSerial::get_instance(usart::USART_Base::USART1_BASE, NO_PIN, NO_PIN)); +#endif +#if USING_HW_SERIAL2 + MSerialT MSerial2(true, MarlinSerial::get_instance(usart::USART_Base::USART2_BASE, NO_PIN, NO_PIN)); +#endif +#if USING_HW_SERIAL3 + MSerialT MSerial3(true, MarlinSerial::get_instance(usart::USART_Base::UART3_BASE, NO_PIN, NO_PIN)); +#endif +#if USING_HW_SERIAL4 + MSerialT MSerial4(true, MarlinSerial::get_instance(usart::USART_Base::UART4_BASE, NO_PIN, NO_PIN)); +#endif + +#if ENABLED(EMERGENCY_PARSER) + // This callback needs to access the specific MarlinSerial instance + // We'll use a static pointer to track the current instance + static MarlinSerial* current_serial_instance = nullptr; + + static void emergency_callback() { + if (!current_serial_instance) return; + const auto last_data = current_serial_instance->get_last_data(); + emergency_parser.update(current_serial_instance->emergency_state, last_data); + } + + void MarlinSerial::register_emergency_callback(void (*callback)()) { + usart_.register_interrupt_callback(usart::Interrupt_Type::INTR_RBNEIE, callback); + } +#endif + +void MarlinSerial::begin(unsigned long baudrate, uint16_t config) { + UsartSerial::begin(baudrate, config, ENABLED(SERIAL_DMA)); + #if ENABLED(EMERGENCY_PARSER) && DISABLED(SERIAL_DMA) + current_serial_instance = this; + register_emergency_callback(emergency_callback); + #endif +} + +void MarlinSerial::updateRxDmaBuffer() { + #if ENABLED(EMERGENCY_PARSER) + // Get the number of bytes available in the receive buffer + const size_t available_bytes = usart_.available_for_read(true); + + // Process only the available data + for (size_t i = 0; i < available_bytes; ++i) { + uint8_t data; + if (usart_.read_rx_buffer(data)) + emergency_parser.update(emergency_state, data); + } + #endif + // Call the base class implementation to handle any additional updates + UsartSerial::updateRxDmaBuffer(); +} + +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/MarlinSerial.h b/Marlin/src/HAL/GD32_MFL/MarlinSerial.h new file mode 100644 index 0000000000..6b33ce0e61 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/MarlinSerial.h @@ -0,0 +1,75 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif + +#include + +#include "../../core/serial_hook.h" + +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 4 + +#include "../shared/serial_ports.h" + +#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() +#endif + +using namespace arduino; + +struct MarlinSerial : public UsartSerial { + static auto get_instance(usart::USART_Base Base, pin_size_t rxPin = NO_PIN, pin_size_t txPin = NO_PIN) -> MarlinSerial&; + + void begin(unsigned long baudrate, uint16_t config); + inline void begin(unsigned long baudrate) { begin(baudrate, SERIAL_8N1); } + void updateRxDmaBuffer(); + + #if DISABLED(SERIAL_DMA) + FORCE_INLINE static uint8_t buffer_overruns() { return 0; } + #endif + + #if ENABLED(EMERGENCY_PARSER) + EmergencyParser::State emergency_state; + + // Accessor method to get the last received byte + auto get_last_data() -> uint8_t { return usart_.get_last_data(); } + + // Register the emergency callback + void register_emergency_callback(void (*callback)()); + #endif + +protected: + using UsartSerial::UsartSerial; +}; + +typedef Serial1Class MSerialT; +extern MSerialT MSerial0; +extern MSerialT MSerial1; +extern MSerialT MSerial2; +extern MSerialT MSerial3; +extern MSerialT MSerial4; diff --git a/Marlin/src/HAL/GD32_MFL/MinSerial.cpp b/Marlin/src/HAL/GD32_MFL/MinSerial.cpp new file mode 100644 index 0000000000..2cc79c8853 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/MinSerial.cpp @@ -0,0 +1,163 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ARDUINO_ARCH_MFL + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(POSTMORTEM_DEBUGGING) +#include "../shared/MinSerial.h" + +// Base addresses for USART peripherals +static constexpr uintptr_t USART_base[] = { + 0x40013800, // USART0 + 0x40004400, // USART1 + 0x40004800, // USART2 + 0x40004C00, // UART3 + 0x40005000 // UART4 +}; + +// Register offsets +static constexpr uint32_t STAT0_OFFSET = 0x00U; +static constexpr uint32_t DATA_OFFSET = 0x04U; +static constexpr uint32_t BAUD_OFFSET = 0x08U; +static constexpr uint32_t CTL0_OFFSET = 0x0CU; +static constexpr uint32_t CTL1_OFFSET = 0x14U; + +// Bit positions +static constexpr uint32_t TBE_BIT = 7; +static constexpr uint32_t TEN_BIT = 3; +static constexpr uint32_t UEN_BIT = 13; + +// NVIC interrupt numbers for USART +static constexpr int nvicUART[] = { 37, 38, 39, 52, 53 }; + +// RCU PCLK values for USART +static constexpr rcu::RCU_PCLK clockRegs[] = { + rcu::RCU_PCLK::PCLK_USART0, + rcu::RCU_PCLK::PCLK_USART1, + rcu::RCU_PCLK::PCLK_USART2, + rcu::RCU_PCLK::PCLK_UART3, + rcu::RCU_PCLK::PCLK_UART4 +}; + +// Memory barrier instructions +#define isb() __asm__ __volatile__ ("isb" : : : "memory") +#define dsb() __asm__ __volatile__ ("dsb" : : : "memory") +#define sw_barrier() __asm__ volatile("" : : : "memory") + +// Direct register access macros +#define USART_REG(offset) (*(volatile uint32_t*)(USART_base[SERIAL_PORT] + (offset))) +#define USART_STAT0 USART_REG(STAT0_OFFSET) +#define USART_DATA USART_REG(DATA_OFFSET) +#define USART_BAUD USART_REG(BAUD_OFFSET) +#define USART_CTL0 USART_REG(CTL0_OFFSET) +#define USART_CTL1 USART_REG(CTL1_OFFSET) + +// Bit manipulation macros +#define READ_BIT(reg, bit) (((reg) >> (bit)) & 1U) +#define SET_BIT(reg, bit) ((reg) |= (1U << (bit))) +#define CLEAR_BIT(reg, bit) ((reg) &= ~(1U << (bit))) + +// Initializes the MinSerial interface. +// This function sets up the USART interface for serial communication. +// If the selected serial port is not a hardware port, it disables the severe error reporting feature. +static void MinSerialBegin() { + #if !WITHIN(SERIAL_PORT, 0, 4) + #warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error." + #warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port." + #else + int nvicIndex = nvicUART[SERIAL_PORT]; + + // NVIC base address for interrupt disable + struct NVICMin { + volatile uint32_t ISER[32]; + volatile uint32_t ICER[32]; + }; + NVICMin *nvicBase = (NVICMin*)0xE000E100; + + SBI32(nvicBase->ICER[nvicIndex >> 5], nvicIndex & 0x1F); + + // We require memory barriers to properly disable interrupts + // (https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the) + dsb(); + isb(); + + // Get the RCU PCLK for this USART + rcu::RCU_PCLK pclk = clockRegs[SERIAL_PORT]; + + // Disable then enable usart peripheral clocks + rcu::RCU_DEVICE.set_pclk_enable(pclk, false); + rcu::RCU_DEVICE.set_pclk_enable(pclk, true); + + // Save current baudrate + uint32_t baudrate = USART_BAUD; + + // Reset USART control registers + USART_CTL0 = 0; + USART_CTL1 = 0; // 1 stop bit + + // Restore baudrate + USART_BAUD = baudrate; + + // Enable transmitter and USART (8 bits, no parity, 1 stop bit) + SET_BIT(USART_CTL0, TEN_BIT); + SET_BIT(USART_CTL0, UEN_BIT); + #endif +} + +// Writes a single character to the serial port. +static void MinSerialWrite(char c) { + #if WITHIN(SERIAL_PORT, 0, 4) + // Wait until transmit buffer is empty + while (!READ_BIT(USART_STAT0, TBE_BIT)) { + hal.watchdog_refresh(); + sw_barrier(); + } + // Write character to data register + USART_DATA = c; + #endif +} + +// Installs the minimum serial interface. +// Sets the HAL_min_serial_init and HAL_min_serial_out function pointers to MinSerialBegin and MinSerialWrite respectively. +void install_min_serial() { + HAL_min_serial_init = &MinSerialBegin; + HAL_min_serial_out = &MinSerialWrite; +} + +extern "C" { + // A low-level assembly-based jump handler. + // Unconditionally branches to the CommonHandler_ASM function. + __attribute__((naked, aligned(4))) void JumpHandler_ASM() { + __asm__ __volatile__ ("b CommonHandler_ASM\n"); + } + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler(); +} + +#endif // POSTMORTEM_DEBUGGING +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/README.md b/Marlin/src/HAL/GD32_MFL/README.md new file mode 100644 index 0000000000..61800eda1c --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/README.md @@ -0,0 +1,9 @@ +# Generic GD32 HAL based on the MFL Arduino Core + +This HAL is eventually intended to act as the generic HAL for all GD32 chips using the MFL library. + +Currently it supports: + +- GD32F303RET6 + +Targeting the official [MFL Arduino Core](https://github.com/bnmguy/ArduinoCore_MFL). diff --git a/Marlin/src/HAL/GD32_MFL/Servo.cpp b/Marlin/src/HAL/GD32_MFL/Servo.cpp new file mode 100644 index 0000000000..6cbcbc049b --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/Servo.cpp @@ -0,0 +1,125 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ARDUINO_ARCH_MFL + +#include "../../inc/MarlinConfig.h" + +#if HAS_SERVOS + +#include "Servo.h" + +static uint_fast8_t servoCount = 0; +static libServo* servos[NUM_SERVOS] = {0}; +constexpr millis_t servoDelay[] = SERVO_DELAY; +static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); + +// Initialize to the default timer priority. This will be overridden by a call from timers.cpp. +// This allows all timer interrupt priorities to be managed from a single location in the HAL. +static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 12, 0); + +// This must be called after the MFL Servo class has initialized the timer. +// To be safe this is currently called after every call to attach(). +static void fixServoTimerInterruptPriority() { + auto& servoTimerIdx = GeneralTimer::get_instance(static_cast(TIMER_SERVO)); + NVIC_SetPriority(servoTimerIdx.getTimerUpIRQ(), servo_interrupt_priority); +} + +// Default constructor for libServo class. +// Initializes the servo delay, pause state, and pause value. +// Registers the servo instance in the servos array. +libServo::libServo() : + delay(servoDelay[servoCount]), + was_attached_before_pause(false), + value_before_pause(0) +{ + servos[servoCount++] = this; +} + +// Attaches a servo to a specified pin. +int8_t libServo::attach(const int pin) { + if (servoCount >= MAX_SERVOS) return -1; + if (pin > 0) servoPin = pin; + auto result = mflServo.attach(servoPin); + fixServoTimerInterruptPriority(); + return result; +} + +// Attaches a servo to a specified pin with minimum and maximum pulse widths. +int8_t libServo::attach(const int pin, const int min, const int max) { + if (servoCount >= MAX_SERVOS) return -1; + if (pin > 0) servoPin = pin; + auto result = mflServo.attach(servoPin, min, max); + fixServoTimerInterruptPriority(); + return result; +} + +// Moves the servo to a specified position. +void libServo::move(const int value) { + if (attach(0) >= 0) { + mflServo.write(value); + safe_delay(delay); + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); + } +} + +// Pause the servo by detaching it and storing its current state. +void libServo::pause() { + was_attached_before_pause = mflServo.attached(); + if (was_attached_before_pause) { + value_before_pause = mflServo.read(); + mflServo.detach(); + } +} + +// Resume a previously paused servo. +// If the servo was attached before the pause, this function re-attaches +// the servo and moves it to the position it was in before the pause. +void libServo::resume() { + if (was_attached_before_pause) { + attach(); + move(value_before_pause); + } +} + +// Pause all servos by stopping their timers. +void libServo::pause_all_servos() { + for (auto& servo : servos) + if (servo) servo->pause(); +} + +// Resume all paused servos by starting their timers. +void libServo::resume_all_servos() { + for (auto& servo : servos) + if (servo) servo->resume(); +} + +// Set the interrupt priority for the servo. +// @param preemptPriority The preempt priority level. +// @param subPriority The sub priority level. +void libServo::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) { + servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority); +} + +#endif // HAS_SERVOS +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/Servo.h b/Marlin/src/HAL/GD32_MFL/Servo.h new file mode 100644 index 0000000000..80cff46ff8 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/Servo.h @@ -0,0 +1,56 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include + +#include "../../core/millis_t.h" + +// Inherit and expand on the official library +class libServo { +public: + libServo(); + + int8_t attach(const int pin = 0); // pin == 0 uses value from previous call + int8_t attach(const int pin, const int min, const int max); + void detach() { mflServo.detach(); } + + int read() { return mflServo.read(); } + void move(const int value); + + void pause(); + void resume(); + + static void pause_all_servos(); + static void resume_all_servos(); + + static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority); + +private: + Servo mflServo; + + int servoPin = 0; + millis_t delay = 0; + + bool was_attached_before_pause; + int value_before_pause; +}; diff --git a/Marlin/src/HAL/GD32_MFL/dogm/u8g_com_mfl_swspi.cpp b/Marlin/src/HAL/GD32_MFL/dogm/u8g_com_mfl_swspi.cpp new file mode 100644 index 0000000000..b36cbfe44d --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/dogm/u8g_com_mfl_swspi.cpp @@ -0,0 +1,129 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm / Ryan Power + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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_MFL + +#include "../../../inc/MarlinConfig.h" + +#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) + +#include +#include "../../shared/HAL_SPI.h" + +#define nop asm volatile ("\tnop\n") + +static inline uint8_t swSpiTransfer_mode_0(uint8_t b) { + for (uint8_t i = 0; i < 8; ++i) { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + WRITE(DOGLCD_SCK, HIGH); + WRITE(DOGLCD_MOSI, state); + b <<= 1; + WRITE(DOGLCD_SCK, LOW); + } + return b; +} + +static inline uint8_t swSpiTransfer_mode_3(uint8_t b) { + for (uint8_t i = 0; i < 8; ++i) { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + WRITE(DOGLCD_SCK, LOW); + WRITE(DOGLCD_MOSI, state); + b <<= 1; + WRITE(DOGLCD_SCK, HIGH); + } + return b; +} + +static void u8g_sw_spi_shift_out(uint8_t val) { + #if U8G_SPI_USE_MODE_3 + swSpiTransfer_mode_3(val); + #else + swSpiTransfer_mode_0(val); + #endif +} + +static void swSpiInit() { + #if PIN_EXISTS(LCD_RESET) + SET_OUTPUT(LCD_RESET_PIN); + #endif + SET_OUTPUT(DOGLCD_A0); + OUT_WRITE(DOGLCD_SCK, LOW); + OUT_WRITE(DOGLCD_MOSI, LOW); + OUT_WRITE(DOGLCD_CS, HIGH); +} + +uint8_t u8g_com_HAL_MFL_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + switch (msg) { + case U8G_COM_MSG_INIT: + swSpiInit(); + break; + case U8G_COM_MSG_STOP: + break; + case U8G_COM_MSG_RESET: + #if PIN_EXISTS(LCD_RESET) + WRITE(LCD_RESET_PIN, arg_val); + #endif + break; + case U8G_COM_MSG_CHIP_SELECT: + #if U8G_SPI_USE_MODE_3 // This LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + WRITE(DOGLCD_SCK, HIGH); // Set SCK to mode 3 idle state before CS goes active + WRITE(DOGLCD_CS, LOW); + nop; // Hold SCK high for a few ns + nop; + } + else { + WRITE(DOGLCD_CS, HIGH); + WRITE(DOGLCD_SCK, LOW); // Set SCK to mode 0 idle state after CS goes inactive + } + #else + WRITE(DOGLCD_CS, !arg_val); + #endif + break; + case U8G_COM_MSG_WRITE_BYTE: + u8g_sw_spi_shift_out(arg_val); + break; + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t* ptr = (uint8_t*)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(*ptr++); + arg_val--; + } + } break; + case U8G_COM_MSG_WRITE_SEQ_P: { + uint8_t* ptr = (uint8_t*)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } break; + case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1) + WRITE(DOGLCD_A0, arg_val); + break; + } + return 1; +} + +#endif // HAS_MARLINUI_U8GLIB && FORCE_SOFT_SPI +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_bl24cxx.cpp b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_bl24cxx.cpp new file mode 100644 index 0000000000..1053c80a41 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_bl24cxx.cpp @@ -0,0 +1,93 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../../platforms.h" + +#ifdef ARDUINO_ARCH_MFL + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM." +#endif + +size_t PersistentStore::capacity() { + return MARLIN_EEPROM_SIZE - eeprom_exclude_size; +} + +bool PersistentStore::access_start() { + eeprom_init(); + return true; +} + +bool PersistentStore::access_finish() { + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; + while (size--) { + uint8_t v = *value; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); + // EPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + + crc16(crc, &v, 1); + pos++; + value++; + } + + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + + return false; +} + +#endif // IIC_BL24CXX_EEPROM +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_if_iic.cpp b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_if_iic.cpp new file mode 100644 index 0000000000..765c997e1f --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_if_iic.cpp @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Platform-independent Arduino functions for I2C EEPROM. + * Enable USE_SHARED_EEPROM if not supplied by the framework. + */ + +#include "../../platforms.h" + +#ifdef ARDUINO_ARCH_MFL + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../../../libs/BL24CXX.h" +#include "../../shared/eeprom_if.h" + +void eeprom_init() { + BL24CXX::init(); +} + +void eeprom_write_byte(uint8_t *pos, uint8_t value) { + const unsigned eeprom_address = (unsigned)pos; + BL24CXX::writeOneByte(eeprom_address, value); +} + +uint8_t eeprom_read_byte(uint8_t *pos) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::readOneByte(eeprom_address); +} + +#endif // IIC_BL24CXX_EEPROM +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_wired.cpp b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_wired.cpp new file mode 100644 index 0000000000..8860e53a62 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_wired.cpp @@ -0,0 +1,96 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ARDUINO_ARCH_MFL + +#include "../../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif + +size_t PersistentStore::capacity() { + return MARLIN_EEPROM_SIZE - eeprom_exclude_size; +} + +bool PersistentStore::access_start() { + eeprom_init(); + return true; +} + +bool PersistentStore::access_finish() { + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; + while (size--) { + uint8_t v = *value; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + // Avoid triggering watchdog during long EEPROM writes + if (++written & 0x7F) + delay(2); + else + safe_delay(2); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); + if (writing) + *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + + return false; +} + +#endif // USE_WIRED_EEPROM +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/endstop_interrupts.h b/Marlin/src/HAL/GD32_MFL/endstop_interrupts.h new file mode 100644 index 0000000000..175dec3959 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/endstop_interrupts.h @@ -0,0 +1,61 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../module/endstops.h" + +// One ISR for all EXT-Interrupts +void endstop_ISR() { endstops.update(); } + +void setup_endstop_interrupts() { + #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); +} diff --git a/Marlin/src/HAL/GD32_MFL/fast_pwm.cpp b/Marlin/src/HAL/GD32_MFL/fast_pwm.cpp new file mode 100644 index 0000000000..9fba673efc --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/fast_pwm.cpp @@ -0,0 +1,97 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ARDUINO_ARCH_MFL + +#include "../../inc/MarlinConfig.h" + +#include +#include +#include "timers.h" + +static uint16_t timer_frequency[TIMER_COUNT]; + +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale, const bool invert) { + // Calculate duty cycle based on inversion flag + const uint16_t duty = invert ? scale - value : value; + + // Check if the pin supports PWM + if (PWM_PIN(pin)) { + // Get the timer peripheral base associated with the pin + const auto timer_base = getPinOpsPeripheralBase(TIMER_PinOps, static_cast(pin)); + + // Initialize the timer instance + auto& TimerInstance = GeneralTimer::get_instance(timer_base); + + // Get channel and previous channel mode + const auto channel = getPackedPinChannel(getPackedPinOps(TIMER_PinOps, static_cast(pin))); + const InputOutputMode previous = TimerInstance.getChannelMode(channel); + + if (timer_frequency[static_cast(timer_base)] == 0) { + set_pwm_frequency(pin, PWM_FREQUENCY); + } + + // Set the PWM duty cycle + TimerInstance.setCaptureCompare(channel, duty, CCFormat::B8); + + // Configure pin as PWM output + pinOpsPinout(TIMER_PinOps, static_cast(pin)); + + // Set channel mode if not already set and start timer + if (previous != InputOutputMode::PWM0) { + TimerInstance.setChannelMode(channel, InputOutputMode::PWM0, static_cast(pin)); + TimerInstance.start(); + } + } else { + pinMode(pin, OUTPUT); + digitalWrite(pin, duty < scale / 2 ? LOW : HIGH); + } +} + +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { + // Check if the pin supports PWM + if (!PWM_PIN(pin)) return; + + // Get the timer peripheral base associated with the pin + const auto timer_base = getPinOpsPeripheralBase(TIMER_PinOps, static_cast(pin)); + + // Guard against modifying protected timers + #ifdef STEP_TIMER + if (timer_base == static_cast(STEP_TIMER)) return; + #endif + #ifdef TEMP_TIMER + if (timer_base == static_cast(TEMP_TIMER)) return; + #endif + #if defined(PULSE_TIMER) && MF_TIMER_PULSE != MF_TIMER_STEP + if (timer_base == static_cast(PULSE_TIMER)) return; + #endif + + // Initialize the timer instance + auto& TimerInstance = GeneralTimer::get_instance(timer_base); + + TimerInstance.setRolloverValue(f_desired, TimerFormat::HERTZ); + timer_frequency[timer_base_to_index(timer_base)] = f_desired; +} + +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/fastio.h b/Marlin/src/HAL/GD32_MFL/fastio.h new file mode 100644 index 0000000000..11020f3e52 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/fastio.h @@ -0,0 +1,86 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// Fast I/O interfaces for GD32 + +#include +#include +#include +#include + +template +FORCE_INLINE static void fast_write_pin_wrapper(pin_size_t IO, T V) { + const PortPinPair& pp = port_pin_map[IO]; + gpio::fast_write_pin(pp.port, pp.pin, static_cast(V)); +} + +FORCE_INLINE static auto fast_read_pin_wrapper(pin_size_t IO) -> bool { + const PortPinPair& pp = port_pin_map[IO]; + return gpio::fast_read_pin(pp.port, pp.pin); +} + +FORCE_INLINE static void fast_toggle_pin_wrapper(pin_size_t IO) { + const PortPinPair& pp = port_pin_map[IO]; + gpio::fast_toggle_pin(pp.port, pp.pin); +} + +// ------------------------ +// Defines +// ------------------------ + +#ifndef PWM + #define PWM OUTPUT +#endif + +#define _WRITE(IO, V) fast_write_pin_wrapper(IO, V) +#define _READ(IO) fast_read_pin_wrapper(IO) +#define _TOGGLE(IO) fast_toggle_pin_wrapper(IO) + +#define _GET_MODE(IO) +#define _SET_MODE(IO, M) pinMode((IO), (M)) +#define _SET_OUTPUT(IO) pinMode((IO), OUTPUT) +#define _SET_OUTPUT_OD(IO) pinMode((IO), OUTPUT_OPEN_DRAIN) + +#define WRITE(IO, V) _WRITE((IO), (V)) +#define READ(IO) _READ(IO) +#define TOGGLE(IO) _TOGGLE(IO) + +#define OUT_WRITE(IO, V) do { _SET_OUTPUT(IO); WRITE((IO), (V)); } while (0) +#define OUT_WRITE_OD(IO, V) do { _SET_OUTPUT_OD(IO); WRITE((IO), (V)); } while (0) + +#define SET_INPUT(IO) _SET_MODE((IO), INPUT) +#define SET_INPUT_PULLUP(IO) _SET_MODE((IO), INPUT_PULLUP) +#define SET_INPUT_PULLDOWN(IO) _SET_MODE((IO), INPUT_PULLDOWN) +#define SET_OUTPUT(IO) OUT_WRITE((IO), LOW) +#define SET_OUTPUT_OD(IO) OUT_WRITE_OD((IO), LOW) +#define SET_PWM(IO) _SET_MODE((IO), PWM) + +#define IS_INPUT(IO) +#define IS_OUTPUT(IO) + +#define PWM_PIN(P) isPinInPinOps(TIMER_PinOps, P) +#define NO_COMPILE_TIME_PWM + +// Wrappers for digitalRead and digitalWrite +#define extDigitalRead(IO) digitalRead(IO) +#define extDigitalWrite(IO, V) digitalWrite((IO), (V)) diff --git a/Marlin/src/HAL/GD32_MFL/inc/Conditionals_LCD.h b/Marlin/src/HAL/GD32_MFL/inc/Conditionals_LCD.h new file mode 100644 index 0000000000..379ecfa7f0 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/inc/Conditionals_LCD.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) + #define U8G_SW_SPI_MFL 1 +#endif diff --git a/Marlin/src/HAL/GD32_MFL/inc/Conditionals_adv.h b/Marlin/src/HAL/GD32_MFL/inc/Conditionals_adv.h new file mode 100644 index 0000000000..6df84f6f92 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/inc/Conditionals_adv.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ALL(HAS_MEDIA, USBD_USE_CDC_MSC) + #define HAS_SD_HOST_DRIVE 1 +#endif diff --git a/Marlin/src/HAL/GD32_MFL/inc/Conditionals_post.h b/Marlin/src/HAL/GD32_MFL/inc/Conditionals_post.h new file mode 100644 index 0000000000..a3db122682 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/inc/Conditionals_post.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 no real or emulated EEPROM selected, fall back to SD emulation +#if USE_FALLBACK_EEPROM + #define SDCARD_EEPROM_EMULATION +#elif ANY(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 +#endif diff --git a/Marlin/src/HAL/GD32_MFL/inc/Conditionals_type.h b/Marlin/src/HAL/GD32_MFL/inc/Conditionals_type.h new file mode 100644 index 0000000000..92cc457df5 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/GD32_MFL/inc/SanityCheck.h b/Marlin/src/HAL/GD32_MFL/inc/SanityCheck.h new file mode 100644 index 0000000000..366765dcd5 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/inc/SanityCheck.h @@ -0,0 +1,97 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// Test MFL GD32 specific configuration values for errors at compile-time. +#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA + #undef SDCARD_EEPROM_EMULATION // avoid additional error noise + #if USE_FALLBACK_EEPROM + #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." + #endif + #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." +#endif + +#if ENABLED(FLASH_EEPROM_LEVELING) + #error "FLASH_EEPROM_LEVELING is not supported on GD32." +#endif + +#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on GD32." +#elif ENABLED(SERIAL_STATS_DROPPED_RX) + #error "SERIAL_STATS_DROPPED_RX is not supported on GD32." +#endif + +#if TEMP_SENSOR_SOC && defined(ATEMP) && TEMP_SOC_PIN != ATEMP + #error "TEMP_SENSOR_SOC requires 'TEMP_SOC_PIN ATEMP' on GD32" +#endif + +// Check for common serial pin conflicts +#define _CHECK_SERIAL_PIN(N) (( \ + BTN_EN1 == N || BTN_EN2 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN0_PIN == N || \ + SDIO_D2_PIN == N || SDIO_D3_PIN == N || SDIO_CK_PIN == N || SDIO_CMD_PIN == N || \ + Y_STEP_PIN == N || Y_ENABLE_PIN == N || E0_ENABLE_PIN == N || POWER_LOSS_PIN == N \ + )) + +#define CHECK_SERIAL_PIN(T, N) defined(UART##N##_##T##_PIN) && _CHECK_SERIAL_PIN(UART##N##_##T##_PIN) + +#if SERIAL_IN_USE(0) + #if CHECK_SERIAL_PIN(TX, 0) + #error "Serial Port 0 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX, 0) + #error "Serial Port 0 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(1) + #if CHECK_SERIAL_PIN(TX, 1) + #error "Serial Port 1 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX, 1) + #error "Serial Port 1 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(2) + #if CHECK_SERIAL_PIN(TX, 2) + #error "Serial Port 2 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX, 2) + #error "Serial Port 2 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(3) + #if CHECK_SERIAL_PIN(TX, 3) + #error "Serial Port 3 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX, 3) + #error "Serial Port 3 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(4) + #if CHECK_SERIAL_PIN(TX, 4) + #error "Serial Port 4 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX, 4) + #error "Serial Port 4 RX IO pins conflict with another pin on the board." + #endif +#endif +#undef CHECK_SERIAL_PIN +#undef _CHECK_SERIAL_PIN diff --git a/Marlin/src/HAL/GD32_MFL/pinsDebug.h b/Marlin/src/HAL/GD32_MFL/pinsDebug.h new file mode 100644 index 0000000000..be7e4ce1ba --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/pinsDebug.h @@ -0,0 +1,104 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * Pins Debugging for GD32 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + +#include "../../inc/MarlinConfig.h" +#include +#include +#include + +#ifndef TOTAL_PIN_COUNT + #error "Expected TOTAL_PIN_COUNT not found." +#endif + +#define NUM_DIGITAL_PINS TOTAL_PIN_COUNT +#define NUMBER_PINS_TOTAL TOTAL_PIN_COUNT + +#define getPinByIndex(x) pin_t(pin_array[x].pin) +#define isValidPin(P) WITHIN(P, 0, (NUM_DIGITAL_PINS - 1)) +#define digitalRead_mod(P) extDigitalRead(P) +#define printPinNumber(P) do { sprintf_P(buffer, PSTR("%3hd "), pin_t(P)); SERIAL_ECHO(buffer); } while (0) +#define printPinAnalog(P) do { sprintf_P(buffer, PSTR(" (A%2d) "), pin_t(getAdcChannelFromPin(P))); SERIAL_ECHO(buffer); } while (0) +#define printPinNameByIndex(x) do { sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); } while (0) + +#define MULTI_NAME_PAD 21 // Space needed to be pretty if not first name assigned to a pin + +#ifndef M43_NEVER_TOUCH + #define M43_NEVER_TOUCH(x) WITHIN(x, 9, 10) // SERIAL pins: PA9(TX) PA10(RX) +#endif + +bool isAnalogPin(const pin_t pin) { + if (!isValidPin(pin)) return false; + + if (getAdcChannel(pin) != adc::ADC_Channel::INVALID) { + const PortPinPair& pp = port_pin_map[pin]; + auto& instance = gpio::GPIO::get_instance(pp.port).value(); + return instance.get_pin_mode(pp.pin) == gpio::Pin_Mode::ANALOG && !M43_NEVER_TOUCH(pin); + } + + return false; +} + +bool getValidPinMode(const pin_t pin) { + if (!isValidPin(pin)) return false; + + const PortPinPair& pp = port_pin_map[pin]; + auto& instance = gpio::GPIO::get_instance(pp.port).value(); + gpio::Pin_Mode mode = instance.get_pin_mode(pp.pin); + + return mode != gpio::Pin_Mode::ANALOG && mode != gpio::Pin_Mode::INPUT_FLOATING && + mode != gpio::Pin_Mode::INPUT_PULLUP && mode != gpio::Pin_Mode::INPUT_PULLDOWN; +} + +bool getPinIsDigitalByIndex(const int16_t index) { + const pin_t pin = getPinByIndex(index); + return (!isAnalogPin(pin)); +} + +int8_t digitalPinToAnalogIndex(const pin_t pin) { + if (!isValidPin(pin) || !isAnalogPin(pin)) return -1; + return pin; // Analog and digital pin indexes are shared +} + +bool pwm_status(const pin_t pin) { return false; } +void printPinPWM(const pin_t pin) { /* TODO */ } +void printPinPort(const pin_t pin) { /* TODO */ } diff --git a/Marlin/src/HAL/GD32_MFL/sd/SDCard.cpp b/Marlin/src/HAL/GD32_MFL/sd/SDCard.cpp new file mode 100644 index 0000000000..2e7ba4dfd9 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/sd/SDCard.cpp @@ -0,0 +1,1022 @@ +// +// MFL gd32f30x SDCARD using DMA through SDIO in C++ +// +// Copyright (C) 2025 B. Mourit +// +// This software 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 software is distributed in the hope that 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 software. +// If not, see . +// + +#include "../../platforms.h" + +#ifdef ARDUINO_ARCH_MFL + +#include "../../../inc/MarlinConfig.h" +#include "../../shared/Delay.h" + +#include "SDCard.h" +#include +#include + +namespace sdio { + +auto CardDMA::get_instance() -> CardDMA& { + static CardDMA instance; + return instance; +} + +CardDMA::CardDMA() : + sdcard_csd_{0U, 0U, 0U, 0U}, + sdcard_cid_{0U, 0U, 0U, 0U}, + sdcard_scr_{0U, 0U}, + desired_clock_(Default_Desired_Clock), + total_bytes_(0U), + sdio_(SDIO::get_instance()), + config_(sdio_.get_config()), + dmaBase_(dma::DMA_Base::DMA1_BASE), + dmaChannel_(dma::DMA_Channel::CHANNEL3), + dma_(dma::DMA::get_instance(dmaBase_, dmaChannel_).value()), + sdcard_rca_(0U), + transfer_error_(SDIO_Error_Type::OK), + interface_version_(Interface_Version::UNKNOWN), + card_type_(Card_Type::UNKNOWN), + current_state_(Operational_State::READY), + transfer_end_(false), + multiblock_(false), + is_rx_(false) +{ +} + +// Initialize card and put in standby state +auto CardDMA::init() -> SDIO_Error_Type { + // Reset SDIO peripheral + sdio_.reset(); + sync_domains(); + + // Initialize SDIO peripheral + // If no SDIO_Config structure is provided the default is used. + // The default provides the parameters for initialization + // using a very low clock speed (typically <= 400KHz). + sdio_.init(); + sync_domains(); + + SDIO_Error_Type result = begin_startup_procedure(); + if (result != SDIO_Error_Type::OK) { + return result; + } + + return card_init(); +} + +// Startup command procedure according to SDIO specification +auto CardDMA::begin_startup_procedure() -> SDIO_Error_Type { + sdio_.set_power_mode(Power_Control::POWER_ON); + sdio_.set_clock_enable(true); + sync_domains(); + + // CMD0 (GO_IDLE_STATE) + if (send_command_and_check(Command_Index::CMD0, 0, Command_Response::RSP_NONE, Wait_Type::WT_NONE, [this]() { + return this->get_command_sent_result(); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD0_FAILED; + } + + // CMD8 + if (send_command_and_check(Command_Index::CMD8, Check_Pattern, Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this]() { + return this->get_r7_result(); + }) != SDIO_Error_Type::OK) { + // V1.0 card + // CMD0 (GO_IDLE_STATE) + interface_version_ = Interface_Version::INTERFACE_V1_1; + if (send_command_and_check(Command_Index::CMD0, 0, Command_Response::RSP_NONE, Wait_Type::WT_NONE, [this]() { + return this->get_command_sent_result(); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD0_FAILED; + } + } else { + // V2.0 card + // CMD55 + interface_version_ = Interface_Version::INTERFACE_V2_0; + if (send_command_and_check(Command_Index::CMD55, 0, Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD55_FAILED; + } + } + + if (send_command_and_check(Command_Index::CMD55, 0, Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD55_FAILED; + } + + return validate_voltage(); +} + +// Voltage validation +auto CardDMA::validate_voltage() -> SDIO_Error_Type { + uint32_t response = 0U; + uint32_t count = 0U; + bool valid_voltage = false; + + while (count < Max_Voltage_Checks && valid_voltage == false) { + if (send_command_and_check(Command_Index::CMD55, 0, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD55_FAILED; + } + + if (send_command_and_check(Command_Index::ACMD41, Voltage_Window | SDCARD_HCS | Switch_1_8V_Capacity, + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::INVALID, index = false, crc = true]() { + return check_sdio_status(cmd, index, crc); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::ACMD41_FAILED; + } + response = sdio_.get_response(Response_Type::RESPONSE0); + valid_voltage = ((response >> 31U) == 1U); + count++; + } + + if (count >= Max_Voltage_Checks) { + return SDIO_Error_Type::INVALID_VOLTAGE; + } + + card_type_ = (response & SDCARD_HCS) ? Card_Type::SDCARD_HIGH_CAPACITY : Card_Type::SDCARD_STANDARD_CAPACITY; + + #if ENABLED(MARLIN_DEV_MODE) + if (card_type_ == Card_Type::SDCARD_HIGH_CAPACITY) { + SERIAL_ECHOPGM("\n SDHC!"); + } else { + SERIAL_ECHOPGM("\n SDSC!"); + } + #endif + + return SDIO_Error_Type::OK; +} + +// Shutdown +void CardDMA::begin_shutdown_procedure() { + sdio_.set_power_mode(Power_Control::POWER_OFF); +} + +// Initialize card +auto CardDMA::card_init() -> SDIO_Error_Type { + if (sdio_.get_power_mode() == static_cast(Power_Control::POWER_OFF)) { + return SDIO_Error_Type::INVALID_OPERATION; + } + + // Skip CID/RCA for IO cards + if (card_type_ != Card_Type::SD_IO_CARD) { + if (send_command_and_check(Command_Index::CMD2, 0U, Command_Response::RSP_LONG, Wait_Type::WT_NONE, + [this, cmd = Command_Index::INVALID, index = false, crc = true]() { + return check_sdio_status(cmd, index, crc); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD2_FAILED; + } + // Store CID + store_cid(); + + // Get RCA + uint16_t r6_rca; + if (send_command_and_check(Command_Index::CMD3, 0U, Command_Response::RSP_SHORT, Wait_Type::WT_NONE, + [this, cmd = Command_Index::CMD3, rca = &r6_rca]() { + return get_r6_result(cmd, rca); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD3_FAILED; + } + // Store RCA + sdcard_rca_ = r6_rca; + if (send_command_and_check(Command_Index::CMD9, static_cast(sdcard_rca_ << RCA_Shift), + Command_Response::RSP_LONG, Wait_Type::WT_NONE, + [this, cmd = Command_Index::INVALID, index = false, crc = true]() { + return check_sdio_status(cmd, index, crc); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD9_FAILED; + } + // Store CSD + store_csd(); + } + + Card_Info card_info; + SDIO_Error_Type result = get_card_specific_data(&card_info); + if (result != SDIO_Error_Type::OK) { + return result; + } + + if (select_deselect() != SDIO_Error_Type::OK) { + return SDIO_Error_Type::SELECT_DESELECT_FAILED; + } + + return SDIO_Error_Type::OK; +} + +auto CardDMA::store_cid() -> SDIO_Error_Type { + // Store the CID register values + sdcard_cid_[0] = sdio_.get_response(Response_Type::RESPONSE0); + sdcard_cid_[1] = sdio_.get_response(Response_Type::RESPONSE1); + sdcard_cid_[2] = sdio_.get_response(Response_Type::RESPONSE2); + sdcard_cid_[3] = sdio_.get_response(Response_Type::RESPONSE3); + + return SDIO_Error_Type::OK; +} + +auto CardDMA::store_csd() -> SDIO_Error_Type { + // Store the CSD register values + sdcard_csd_[0] = sdio_.get_response(Response_Type::RESPONSE0); + sdcard_csd_[1] = sdio_.get_response(Response_Type::RESPONSE1); + sdcard_csd_[2] = sdio_.get_response(Response_Type::RESPONSE2); + sdcard_csd_[3] = sdio_.get_response(Response_Type::RESPONSE3); + + return SDIO_Error_Type::OK; +} + +auto CardDMA::set_hardware_bus_width(Bus_Width width) -> SDIO_Error_Type { + if (card_type_ == Card_Type::SD_MMC || width == Bus_Width::WIDTH_8BIT) { + return SDIO_Error_Type::UNSUPPORTED_FUNCTION; + } + + // Retrieve SCR + SDIO_Error_Type result = get_scr(sdcard_rca_, sdcard_scr_); + if (result != SDIO_Error_Type::OK) { + return result; + } + + // Check and set bus width + // This function is only used to set a higher width than the default 1bit + // so no 1bit configuration logic is required. + if (width == Bus_Width::WIDTH_4BIT) { + // Send CMD55 (APP_CMD) + if (send_command_and_check(Command_Index::CMD55, static_cast(sdcard_rca_ << RCA_Shift), Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD55_FAILED; + } + + // Send ACMD6 (SET_BUS_WIDTH) + if (send_command_and_check(Command_Index::ACMD6, 2U, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::ACMD6]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::ACMD6_FAILED; + } + + #if ENABLED(MARLIN_DEV_MODE) + SERIAL_ECHOPGM("\n wide bus set!"); + #endif + sdio_.set_bus_width(Bus_Width::WIDTH_4BIT); + + return SDIO_Error_Type::OK; + } + + return SDIO_Error_Type::UNSUPPORTED_FUNCTION; +} + +auto CardDMA::read(uint8_t* buf, uint32_t address, uint32_t count) -> SDIO_Error_Type { + if (current_state_ == Operational_State::READY) { + transfer_error_ = SDIO_Error_Type::OK; + current_state_ = Operational_State::BUSY; + is_rx_ = true; + multiblock_ = (count > 1); + + sdio_.clear_data_state_machine(Transfer_Direction::CARD_TO_SDIO); + + // Enable the interrupts + sdio_.set_interrupt_enable(Interrupt_Type::DTCRCERRIE, true); + sdio_.set_interrupt_enable(Interrupt_Type::DTTMOUTIE, true); + sdio_.set_interrupt_enable(Interrupt_Type::RXOREIE, true); + sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, true); + sdio_.set_interrupt_enable(Interrupt_Type::STBITEIE, true); + + total_bytes_ = BLOCK_SIZE * count; + + // Set DMA transfer parameters + set_dma_parameters(buf, (total_bytes_ / 4U), false); + sdio_.set_dma_enable(true); + + if (card_type_ != Card_Type::SDCARD_HIGH_CAPACITY) { + address *= 512U; + } + + // CMD16 set card block size + if (send_command_and_check(Command_Index::CMD16, BLOCK_SIZE, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD16]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + sdio_.clear_multiple_interrupt_flags(clear_common_flags); + current_state_ = Operational_State::READY; + return SDIO_Error_Type::CMD16_FAILED; + } + + Block_Size block_size = get_data_block_size_index(BLOCK_SIZE); + + sdio_.set_data_state_machine_and_send(Data_Timeout, total_bytes_, block_size, + Transfer_Mode::BLOCK, Transfer_Direction::CARD_TO_SDIO, true); + + // CMD17/CMD18 (READ_SINGLE_BLOCK/READ_MULTIPLE_BLOCKS) send read command + Command_Index read_cmd = (count > 1U) ? Command_Index::CMD18 : Command_Index::CMD17; + if (send_command_and_check(read_cmd, address, + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = read_cmd]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + sdio_.clear_multiple_interrupt_flags(clear_common_flags); + current_state_ = Operational_State::READY; + return (count > 1U) ? SDIO_Error_Type::CMD18_FAILED : SDIO_Error_Type::CMD17_FAILED; + } + return SDIO_Error_Type::OK; + } else { + return SDIO_Error_Type::BUSY; + } +} + +auto CardDMA::write(uint8_t* buf, uint32_t address, uint32_t count) -> SDIO_Error_Type { + // Enable the interrupts + sdio_.set_interrupt_enable(Interrupt_Type::DTCRCERRIE, true); + sdio_.set_interrupt_enable(Interrupt_Type::DTTMOUTIE, true); + sdio_.set_interrupt_enable(Interrupt_Type::STBITEIE, true); + sdio_.set_interrupt_enable(Interrupt_Type::TXUREIE, true); + + if (card_type_ != Card_Type::SDCARD_HIGH_CAPACITY) { + address *= 512U; + } + + // CMD16 + if (send_command_and_check(Command_Index::CMD16, BLOCK_SIZE, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD16]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + sdio_.clear_multiple_interrupt_flags(clear_common_flags); + return SDIO_Error_Type::CMD16_FAILED; + } + + // CMD25/CMD24 (WRITE_MULTIPLE_BLOCK/WRITE_BLOCK) send write command + Command_Index write_cmd = (count > 1U) ? Command_Index::CMD25 : Command_Index::CMD24; + if (send_command_and_check(write_cmd, address, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = write_cmd]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + sdio_.clear_multiple_interrupt_flags(clear_common_flags); + return (count > 1U) ? SDIO_Error_Type::CMD25_FAILED : SDIO_Error_Type::CMD24_FAILED; + } + + total_bytes_ = BLOCK_SIZE * count; + // Start DMA transfer + set_dma_parameters(buf, (total_bytes_ / 4U), true); + sdio_.set_dma_enable(true); + + sdio_.clear_data_state_machine(Transfer_Direction::SDIO_TO_CARD); + Block_Size block_size = get_data_block_size_index(total_bytes_); + + sdio_.set_data_state_machine_and_send(Data_Timeout, total_bytes_, block_size, + Transfer_Mode::BLOCK, Transfer_Direction::SDIO_TO_CARD, true); + + while (dma_.get_flag(dma::Status_Flags::FLAG_FTFIF) || dma_.get_flag(dma::Status_Flags::FLAG_ERRIF)) { + // Wait for the IRQ handler to clear + } + + return SDIO_Error_Type::OK; +} + +auto CardDMA::erase(uint32_t address_start, uint32_t address_end) -> SDIO_Error_Type { + SDIO_Error_Type result = SDIO_Error_Type::OK; + + // Card command classes CSD + uint8_t temp_byte = static_cast((sdcard_csd_[1] & (0xFFU << 24U)) >> 24U); + uint16_t classes = static_cast(temp_byte << 4U); + temp_byte = static_cast((sdcard_csd_[1] & (0xFFU << 16U)) >> 16U); + classes |= static_cast((temp_byte & 0xF0U) >> 4U); + + if ((classes & (1U << static_cast(Card_Command_Class::ERASE))) == Clear) { + return SDIO_Error_Type::UNSUPPORTED_FUNCTION; + } + + uint32_t delay_time = 120000U / sdio_.get_clock_divider(); + + if (sdio_.get_response(Response_Type::RESPONSE0) & Card_Locked) { + return SDIO_Error_Type::LOCK_UNLOCK_FAILED; + } + + // Size is fixed at 512 bytes for SDHC + if (card_type_ != Card_Type::SDCARD_HIGH_CAPACITY) { + address_start *= 512U; + address_end *= 512U; + } + + if ((card_type_ == Card_Type::SDCARD_STANDARD_CAPACITY) || (card_type_ == Card_Type::SDCARD_HIGH_CAPACITY)) { + // CMD32 (ERASE_WR_BLK_START) + if (send_command_and_check(Command_Index::CMD32, address_start, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD32]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD32_FAILED; + } + // CMD33 (ERASE_WR_BLK_END) + if (send_command_and_check(Command_Index::CMD33, address_end, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD33]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD33_FAILED; + } + } + + // CMD38 (ERASE) + if (send_command_and_check(Command_Index::CMD38, 0U, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD38]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD38_FAILED; + } + + // Loop until the counter reaches the calculated time + for (uint32_t count = 0U; count < delay_time; count++) {} + + Card_State card_state; + result = get_card_state(&card_state); + while ((result == SDIO_Error_Type::OK) && ((card_state == Card_State::PROGRAMMING) || (card_state == Card_State::RECEIVE_DATA))) { + result = get_card_state(&card_state); + } + + return result; +} + +void CardDMA::handle_interrupts() { + transfer_error_ = SDIO_Error_Type::OK; + + if (sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_DTEND)) { + sdio_.clear_interrupt_flag(Clear_Flags::FLAG_DTENDC); + // Disable all interrupts + disable_all_interrupts(); + sdio_.set_data_state_machine_enable(false); + + if (multiblock_ && !is_rx_) { + transfer_error_ = stop_transfer(); + if (transfer_error_ != SDIO_Error_Type::OK) { + return; + } + } + + if (!is_rx_) { + sdio_.set_dma_enable(false); + current_state_ = Operational_State::READY; + } + } else if (sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_DTCRCERR) || + sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_DTTMOUT) || + sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_STBITE) || + sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_TXURE) || + sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_RXORE)) { + + if (sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_DTCRCERR)) { + transfer_error_ = SDIO_Error_Type::DATA_CRC_ERROR; + } + if (sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_DTTMOUT)) { + transfer_error_ = SDIO_Error_Type::DATA_TIMEOUT; + } + if (sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_STBITE)) { + transfer_error_ = SDIO_Error_Type::START_BIT_ERROR; + } + if (sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_TXURE)) { + transfer_error_ = SDIO_Error_Type::TX_FIFO_UNDERRUN; + } + if (sdio_.get_interrupt_flag(Interrupt_Flags::FLAG_INTR_RXORE)) { + transfer_error_ = SDIO_Error_Type::RX_FIFO_OVERRUN; + } + sdio_.clear_multiple_interrupt_flags(clear_data_flags); + sdio_.clear_interrupt_flag(Clear_Flags::FLAG_STBITEC); + disable_all_interrupts(); + + dma_.set_transfer_abandon(); + } +} + +auto CardDMA::select_deselect() -> SDIO_Error_Type { + // CMD7 (SELECT/DESELECT_CARD) + if (send_command_and_check(Command_Index::CMD7, static_cast(sdcard_rca_ << RCA_Shift), + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD7]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD7_FAILED; + } + return SDIO_Error_Type::OK; +} + +auto CardDMA::get_card_interface_status(uint32_t* status) -> SDIO_Error_Type { + if (status == nullptr) return SDIO_Error_Type::INVALID_PARAMETER; + + // CMD13 (SEND_STATUS) + if (send_command_and_check(Command_Index::CMD13, static_cast(sdcard_rca_ << RCA_Shift), + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD13]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD13_FAILED; + } + + *status = sdio_.get_response(Response_Type::RESPONSE0); + + return SDIO_Error_Type::OK; +} + +auto CardDMA::get_sdcard_status(uint32_t* status) -> SDIO_Error_Type { + uint32_t count = 0U; + + // CMD16 (SET_BLOCKLEN) + if (send_command_and_check(Command_Index::CMD16, 64U, + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD16]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD16_FAILED; + } + + // CMD55 (APP_CMD) + if (send_command_and_check(Command_Index::CMD55, static_cast(sdcard_rca_ << RCA_Shift), + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD55_FAILED; + } + + sdio_.set_data_state_machine_and_send(Data_Timeout, 64U, Block_Size::BYTES_64, Transfer_Mode::BLOCK, Transfer_Direction::CARD_TO_SDIO, true); + + // ACMD13 (SD_STATUS) + if (send_command_and_check(Command_Index::ACMD13, 0U, + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::ACMD13]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::ACMD13_FAILED; + } + + while (!sdio_.check_scr_flags()) { + if (sdio_.get_flag(Status_Flags::FLAG_RFH)) { + for (count = 0U; count < FIFO_Half_Words; count++) { + *(status + count) = sdio_.read_fifo_word(); + } + status += FIFO_Half_Words; + } + + //SDIO_Error_Type result = SDIO_Error_Type::OK; + if (sdio_.get_flag(Status_Flags::FLAG_DTCRCERR)) { + sdio_.clear_flag(Clear_Flags::FLAG_DTCRCERRC); + return SDIO_Error_Type::DATA_CRC_ERROR; + } else if (sdio_.get_flag(Status_Flags::FLAG_DTTMOUT)) { + sdio_.clear_flag(Clear_Flags::FLAG_DTTMOUTC); + return SDIO_Error_Type::DATA_TIMEOUT; + } else if (sdio_.get_flag(Status_Flags::FLAG_RXORE)) { + sdio_.clear_flag(Clear_Flags::FLAG_RXOREC); + return SDIO_Error_Type::RX_FIFO_OVERRUN; + } else if (sdio_.get_flag(Status_Flags::FLAG_STBITE)) { + sdio_.clear_flag(Clear_Flags::FLAG_STBITEC); + return SDIO_Error_Type::START_BIT_ERROR; + } + while (sdio_.get_flag(Status_Flags::FLAG_RXDTVAL)) { + *status = sdio_.read_fifo_word(); + ++status; + } + + sdio_.clear_multiple_interrupt_flags(clear_data_flags); + status -= 16U; + for (count = 0U; count < 16U; count++) { + status[count] = ((status[count] & 0xFFU) << 24U) | + ((status[count] & (0xFFU << 8U)) << 8U) | + ((status[count] & (0xFFU << 16U)) >> 8U) | + ((status[count] & (0xFFU << 24U)) >> 24U); + } + } + + return SDIO_Error_Type::OK; +} + +void CardDMA::check_dma_complete() { + while ((dma_.get_flag(dma::Status_Flags::FLAG_FTFIF)) || (dma_.get_flag(dma::Status_Flags::FLAG_ERRIF))) { + // Wait for the IRQ handler to clear + } +} + +auto CardDMA::stop_transfer() -> SDIO_Error_Type { + // CMD12 (STOP_TRANSMISSION) + if (send_command_and_check(Command_Index::CMD12, 0, Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD12]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD12_FAILED; + } + return SDIO_Error_Type::OK; +} + +auto CardDMA::get_transfer_state() -> Transfer_State { + Transfer_State transfer_state = Transfer_State::IDLE; + if (sdio_.get_flag(Status_Flags::FLAG_TXRUN) | sdio_.get_flag(Status_Flags::FLAG_RXRUN)) { + transfer_state = Transfer_State::BUSY; + } + + return transfer_state; +} + +[[nodiscard]] auto CardDMA::get_card_capacity() const -> uint32_t { + auto extract_bits = [](uint32_t value, uint8_t start_bit, uint8_t length) -> uint32_t { + return (value >> start_bit) & ((1U << length) - 1U); + }; + + uint32_t capacity = 0U; + uint32_t device_size = 0U; + + if (card_type_ == Card_Type::SDCARD_STANDARD_CAPACITY) { + // Extract fields from CSD data using bit manipulation + uint8_t device_size_high = static_cast(extract_bits(sdcard_csd_[1], 8U, 2U)); // Bits [73:72] + uint8_t device_size_mid = static_cast(extract_bits(sdcard_csd_[1], 0U, 8U)); // Bits [71:64] + uint8_t device_size_low = static_cast(extract_bits(sdcard_csd_[2], 24U, 2U)); // Bits [63:62] + + device_size = static_cast((device_size_high) << 10U) | + static_cast((device_size_mid) << 2U) | + static_cast((device_size_low)); + + uint8_t device_size_multiplier_high = static_cast(extract_bits(sdcard_csd_[2], 16U, 2U)); // Bits [49:48] + uint8_t device_size_multiplier_low = static_cast(extract_bits(sdcard_csd_[2], 8U, 1U)); // Bit [47] + uint8_t device_size_multiplier = static_cast((device_size_multiplier_high << 1U) | device_size_multiplier_low); + uint8_t read_block_length = static_cast(extract_bits(sdcard_csd_[1], 16U, 4U)); // Bits [83:80] + + // Capacity = (device_size + 1) * MULT * BLOCK_LEN + uint32_t mult = static_cast(1U << (device_size_multiplier + 2U)); // MULT = 2 ^ (C_SIZE_MULT + 2) + uint32_t block_length = static_cast(1U << read_block_length); // BLOCK_LEN = 2 ^ READ_BL_LEN + + capacity = (device_size + 1U) * mult * block_length; + capacity /= KILOBYTE; // Convert capacity to kilobytes + + } else if (card_type_ == Card_Type::SDCARD_HIGH_CAPACITY) { + // High-capacity card calculation + uint8_t device_size_high = static_cast(extract_bits(sdcard_csd_[1], 0U, 6U)); // Bits [69:64] + uint8_t device_size_mid = static_cast(extract_bits(sdcard_csd_[2], 24U, 8U)); // Bits [55:48] + uint8_t device_size_low = static_cast(extract_bits(sdcard_csd_[2], 16U, 8U)); // Bits [47:40] + + device_size = static_cast((device_size_high) << 16U) | + static_cast((device_size_mid) << 8U) | + static_cast(device_size_low); + + // Capacity in kilobytes + capacity = (device_size + 1U) * BLOCK_SIZE; + } + + return capacity; +} + +auto CardDMA::get_card_specific_data(Card_Info* info) -> SDIO_Error_Type { + if (info == nullptr) return SDIO_Error_Type::INVALID_PARAMETER; + + // Store basic card information + info->type = card_type_; + info->relative_address = sdcard_rca_; + + // Helper function to convert 32-bit registers to byte array + auto convert_registers_to_bytes = [](const uint32_t* registers, uint8_t* bytes, size_t reg_count) { + for (size_t i = 0U; i < reg_count; ++i) { + for (size_t j = 0U; j < 4U; ++j) { + bytes[i * 4U + j] = (registers[i] >> (24U - j * 8U)) & 0xFFU; + } + } + }; + + // Process CID data + uint8_t cid_bytes[16]; + convert_registers_to_bytes(sdcard_cid_, cid_bytes, 4); + + info->cid = { + .manufacture_id = cid_bytes[0], + .oem_id = static_cast( + (cid_bytes[1] << 8U) | + cid_bytes[2] + ), + .name0 = static_cast( + (cid_bytes[3] << 24U) | + (cid_bytes[4] << 16U) | + (cid_bytes[5] << 8U) | + cid_bytes[6] + ), + .name1 = cid_bytes[7], + .revision = cid_bytes[8], + .serial_number = static_cast( + (cid_bytes[9] << 24U) | + (cid_bytes[10] << 16U) | + (cid_bytes[11] << 8U) | + cid_bytes[12] + ), + .manufacture_date = static_cast( + ((cid_bytes[13] & 0x0FU) << 8U) | + cid_bytes[14] + ), + .checksum = static_cast(((cid_bytes[15] & 0xFEU) >> 1U)) + }; + + // Process CSD data + uint8_t csd_bytes[16]; + convert_registers_to_bytes(sdcard_csd_, csd_bytes, 4U); + + // Fill common CSD fields + info->csd = { + .transfer_speed = csd_bytes[3], + .card_command_class = static_cast((csd_bytes[4] << 4U) | ((csd_bytes[5] & 0xF0U) >> 4U)), + }; + + // Process card-type specific CSD fields and calculate capacity + if (card_type_ == Card_Type::SDCARD_STANDARD_CAPACITY) { + process_sdsc_specific_csd(info, csd_bytes); + } else if (card_type_ == Card_Type::SDCARD_HIGH_CAPACITY) { + process_sdhc_specific_csd(info, csd_bytes); + } + + // Fill remaining common CSD fields + process_common_csd_tail(info, csd_bytes); + + return SDIO_Error_Type::OK; +} + +constexpr auto CardDMA::get_data_block_size_index(uint16_t size) -> Block_Size { + if (size < 1 || size > 16384) return Block_Size::BYTES_1; + + // Check if size is a power of two + if ((size & (size - 1)) != 0) return Block_Size::BYTES_1; + + // Count trailing zeros to find the index + uint16_t index = 0; + while ((size >>= 1) != 0) ++index; + + return static_cast(index); +} + +auto CardDMA::get_card_state(Card_State* card_state) -> SDIO_Error_Type { + // CMD13 (SEND_STATUS) + if (send_command_and_check(Command_Index::CMD13, static_cast(sdcard_rca_ << RCA_Shift), + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD13]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD13_FAILED; + } + + uint32_t response = sdio_.get_response(Response_Type::RESPONSE0); + *card_state = static_cast((response >> 9U) & CardStateMask); + if ((response & All_R1_Error_Bits) == 0U) { + return SDIO_Error_Type::OK; + } + + if (response & All_R1_Error_Bits) { + for (const auto& entry : errorTableR1) { + if (TEST(response, entry.bit_position)) { + return entry.errorType; + } + } + return SDIO_Error_Type::ERROR; + } + + return SDIO_Error_Type::OK; +} + +auto CardDMA::get_command_sent_result() -> SDIO_Error_Type { + constexpr uint32_t MAX_TIMEOUT = 0x00FFFFFFU; + uint32_t timeout = MAX_TIMEOUT; + + // Wait for command sent flag or timeout + while (!sdio_.get_flag(Status_Flags::FLAG_CMDSEND) && timeout) { + --timeout; + } + + // Check if timeout occurred + if (timeout == 0U) { + return SDIO_Error_Type::RESPONSE_TIMEOUT; + } + + // Clear command flags and return success + sdio_.clear_multiple_interrupt_flags(clear_command_flags); + return SDIO_Error_Type::OK; +} + +auto CardDMA::check_sdio_status(Command_Index index, bool check_index, bool ignore_crc) -> SDIO_Error_Type { + // Wait until one of the relevant flags is set + if (!sdio_.wait_cmd_flags()) { + return SDIO_Error_Type::RESPONSE_TIMEOUT; + } + + // Check the cmd received bit first, since noise can sometimes + // cause the timeout bit to get erroneously set + // If cmd was received we can safely ignore other checks + if (sdio_.get_flag(Status_Flags::FLAG_CMDRECV)) { + // If cmd was received, check the index + // Responses that dont do an index check will send an invalid cmd index + if (check_index && (index != Command_Index::INVALID)) { + uint8_t received_idx = sdio_.get_command_index(); + if (received_idx != static_cast(index)) { + sdio_.clear_multiple_interrupt_flags(clear_command_flags); + return SDIO_Error_Type::ILLEGAL_COMMAND; + } + } + + // Command received successfully + sdio_.clear_multiple_interrupt_flags(clear_command_flags); + return SDIO_Error_Type::OK; + } + + // Check for timeout + if (sdio_.get_flag(Status_Flags::FLAG_CMDTMOUT)) { + sdio_.clear_flag(Clear_Flags::FLAG_CMDTMOUTC); + return SDIO_Error_Type::RESPONSE_TIMEOUT; + } + + // Check for CRC error if not ignored + if (!ignore_crc && sdio_.get_flag(Status_Flags::FLAG_CCRCERR)) { + sdio_.clear_flag(Clear_Flags::FLAG_CCRCERRC); + return SDIO_Error_Type::COMMAND_CRC_ERROR; + } + + // Final index check (redundant with the first check, but keeping for safety) + // This code path should rarely be taken due to the earlier checks + if (check_index && (index != Command_Index::INVALID)) { + uint8_t received_idx = sdio_.get_command_index(); + if (received_idx != static_cast(index)) { + sdio_.clear_multiple_interrupt_flags(clear_command_flags); + return SDIO_Error_Type::ILLEGAL_COMMAND; + } + } + + // Clear all flags and return success + sdio_.clear_multiple_interrupt_flags(clear_command_flags); + return SDIO_Error_Type::OK; +} + +auto CardDMA::get_r1_result(Command_Index index) -> SDIO_Error_Type { + SDIO_Error_Type result = check_sdio_status(index, true, false); + if (result != SDIO_Error_Type::OK) return result; + + // Get the R1 response and check for errors + uint32_t response = sdio_.get_response(Response_Type::RESPONSE0); + + if (response & All_R1_Error_Bits) { + for (const auto& entry : errorTableR1) { + if (TEST(response, entry.bit_position)) { + return entry.errorType; + } + } + return SDIO_Error_Type::ERROR; + } + + return SDIO_Error_Type::OK; +} + +auto CardDMA::get_r6_result(Command_Index index, uint16_t* rca) -> SDIO_Error_Type { + SDIO_Error_Type result = check_sdio_status(index, true, false); + if (result != SDIO_Error_Type::OK) return result; + + uint32_t response = sdio_.get_response(Response_Type::RESPONSE0); + + if (response & R6_Error_Bits) { + for (const auto& entry : errorTableR6) { + if (TEST(response, entry.bit_position)) { + return entry.errorType; + } + } + return SDIO_Error_Type::ERROR; + } + *rca = static_cast(response >> 16U); + + return SDIO_Error_Type::OK; +} + +auto CardDMA::get_scr(uint16_t rca, uint32_t* scr) -> SDIO_Error_Type { + uint32_t temp_scr[2] = {0U, 0U}; + uint32_t index_scr = 0U; + + // CMD16 (SET_BLOCKLEN) + if (send_command_and_check(Command_Index::CMD16, 8U, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD16]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD16_FAILED; + } + + // CMD55 (APP_CMD) + if (send_command_and_check(Command_Index::CMD55, static_cast(sdcard_rca_ << RCA_Shift), + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD55_FAILED; + } + + // Set data parameters + sdio_.set_data_state_machine_and_send(Data_Timeout, 8U, Block_Size::BYTES_8, + Transfer_Mode::BLOCK, Transfer_Direction::CARD_TO_SDIO, true); + + // ACMD51 (SEND_SCR) + if (send_command_and_check(Command_Index::ACMD51, 0U, Command_Response::RSP_SHORT, + Wait_Type::WT_NONE, [this, cmd = Command_Index::ACMD51]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::ACMD51_FAILED; + } + + // Store SCR + while (!sdio_.check_scr_flags()) { + if (sdio_.get_flag(Status_Flags::FLAG_RXDTVAL)) { + temp_scr[index_scr++] = sdio_.read_fifo_word(); + } + } + + // Check for errors + if (sdio_.get_flag(Status_Flags::FLAG_DTTMOUT)) { + sdio_.clear_flag(Clear_Flags::FLAG_DTTMOUTC); + return SDIO_Error_Type::DATA_TIMEOUT; + } + else if (sdio_.get_flag(Status_Flags::FLAG_DTCRCERR)) { + sdio_.clear_flag(Clear_Flags::FLAG_DTCRCERRC); + return SDIO_Error_Type::DATA_CRC_ERROR; + } + else if (sdio_.get_flag(Status_Flags::FLAG_RXORE)) { + sdio_.clear_flag(Clear_Flags::FLAG_RXOREC); + return SDIO_Error_Type::RX_FIFO_OVERRUN; + } + + sdio_.clear_multiple_interrupt_flags(clear_data_flags); + + constexpr uint32_t BYTE0_MASK = 0xFFU; + constexpr uint32_t BYTE1_MASK = 0xFF00U; + constexpr uint32_t BYTE2_MASK = 0xFF0000U; + constexpr uint32_t BYTE3_MASK = 0xFF000000U; + + // Byte-swap the SCR values (convert from big-endian to little-endian) + scr[0] = ((temp_scr[1] & BYTE0_MASK) << 24) | + ((temp_scr[1] & BYTE1_MASK) << 8) | + ((temp_scr[1] & BYTE2_MASK) >> 8) | + ((temp_scr[1] & BYTE3_MASK) >> 24); + + scr[1] = ((temp_scr[0] & BYTE0_MASK) << 24) | + ((temp_scr[0] & BYTE1_MASK) << 8) | + ((temp_scr[0] & BYTE2_MASK) >> 8) | + ((temp_scr[0] & BYTE3_MASK) >> 24); + + return SDIO_Error_Type::OK; +} + +// DMA for rx/tx is always DMA1 channel 3 +void CardDMA::set_dma_parameters(uint8_t* buf, uint32_t count, bool is_write) { + constexpr uint32_t flag_bits = (1U << static_cast(dma::INTF_Bits::GIF3)); + dma_.clear_flags(flag_bits); + + // Disable and reset DMA + dma_.set_channel_enable(false); + dma_.clear_channel(); + + dma_.init(dma::DMA_Config{ + .count = count, + .memory_address = static_cast(reinterpret_cast(buf)), + .peripheral_address = static_cast(reinterpret_cast(sdio_.reg_address(SDIO_Regs::FIFO))), + .peripheral_bit_width = dma::Bit_Width::WIDTH_32BIT, + .memory_bit_width = dma::Bit_Width::WIDTH_32BIT, + .peripheral_increase = dma::Increase_Mode::INCREASE_DISABLE, + .memory_increase = dma::Increase_Mode::INCREASE_ENABLE, + .channel_priority = dma::Channel_Priority::MEDIUM_PRIORITY, + .direction = is_write ? dma::Transfer_Direction::M2P : dma::Transfer_Direction::P2M + }); + + dma_.set_memory_to_memory_enable(false); + dma_.set_circulation_mode_enable(false); + + // Enable DMA interrupts for transfer complete and error + dma_.set_interrupt_enable(dma::Interrupt_Type::INTR_FTFIE, true); + dma_.set_interrupt_enable(dma::Interrupt_Type::INTR_ERRIE, true); + + // Start the DMA channel + dma_.set_channel_enable(true); +} + +auto CardDMA::wait_for_card_ready() -> SDIO_Error_Type { + constexpr uint32_t MAX_TIMEOUT = 0x00FFFFFFU; + uint32_t timeout = MAX_TIMEOUT; + uint32_t response = sdio_.get_response(Response_Type::RESPONSE0); + + // Poll until card is ready for data or timeout occurs + while (((response & static_cast(R1_Status::READY_FOR_DATA)) == 0U) && timeout) { + --timeout; + + // CMD13 (SEND_STATUS) + if (send_command_and_check(Command_Index::CMD13, static_cast(sdcard_rca_ << RCA_Shift), + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD13]() { + return get_r1_result(cmd); + }) != SDIO_Error_Type::OK) { + return SDIO_Error_Type::CMD13_FAILED; + } + + // Get updated response + response = sdio_.get_response(Response_Type::RESPONSE0); + } + + // Return error if timeout occurred, otherwise success + return timeout ? SDIO_Error_Type::OK : SDIO_Error_Type::ERROR; +} + +} // namespace sdio + +sdio::CardDMA& CardDMA_I = sdio::CardDMA::get_instance(); + +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/sd/SDCard.h b/Marlin/src/HAL/GD32_MFL/sd/SDCard.h new file mode 100644 index 0000000000..de28c40809 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/sd/SDCard.h @@ -0,0 +1,222 @@ +// +// MFL gd32f30x SDCARD using DMA through SDIO in C++ +// +// Copyright (C) 2025 B. Mourit +// +// This software 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 software is distributed in the hope that 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 software. +// If not, see . +// +#pragma once + +#include "../../../inc/MarlinConfig.h" + +#include + +namespace sdio { + +class DMA; + +class CardDMA { +public: + static auto get_instance() -> CardDMA&; + + // Initialization + auto init() -> SDIO_Error_Type; + auto card_init() -> SDIO_Error_Type; + + // Startup and shutdown procedures + auto begin_startup_procedure() -> SDIO_Error_Type; + void begin_shutdown_procedure(); + + // Configuration + auto set_hardware_bus_width(Bus_Width width) -> SDIO_Error_Type; + auto send_bus_width_command(uint32_t width_value) -> SDIO_Error_Type; + + // Main read/write/erase functions + auto read(uint8_t* buf, uint32_t address, uint32_t count) -> SDIO_Error_Type; + auto write(uint8_t* buf, uint32_t address, uint32_t count) -> SDIO_Error_Type; + auto erase(uint32_t address_start, uint32_t address_end) -> SDIO_Error_Type; + + // Card select + auto select_deselect() -> SDIO_Error_Type; + + // Status and state + auto get_card_interface_status(uint32_t* status) -> SDIO_Error_Type; + auto get_sdcard_status(uint32_t* status) -> SDIO_Error_Type; + auto get_transfer_state() -> Transfer_State; + auto get_card_state(Card_State* card_state) -> SDIO_Error_Type; + auto check_sdio_status(Command_Index index = Command_Index::INVALID, bool check_index = false, bool ignore_crc = false) -> SDIO_Error_Type; + + // DMA + void set_dma_parameters(uint8_t* buf, uint32_t count, bool is_write); + void check_dma_complete(); + + // Stop transfer + auto stop_transfer() -> SDIO_Error_Type; + + // Card information + auto get_card_specific_data(Card_Info* info) -> SDIO_Error_Type; + constexpr auto get_data_block_size_index(uint16_t size) -> Block_Size; + [[nodiscard]] auto get_card_capacity() const -> uint32_t; + + // SDIO configuration + void sdio_configure(const SDIO_Config config) { sdio_.init(config); } + + // Interrupt handler + void handle_interrupts(); + + // Variable stored parameters + auto get_scr(uint16_t rca, uint32_t* scr) -> SDIO_Error_Type; + auto store_cid() -> SDIO_Error_Type; + auto store_csd() -> SDIO_Error_Type; + + // Inlined accessor methods + auto get_config() -> SDIO_Config& { return config_; } + auto get_dma_instance() -> dma::DMA& { return dma_; } + void set_data_end_interrupt() { sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, true); } + void set_sdio_dma_enable(bool enable) { sdio_.set_dma_enable(enable); } + auto get_is_sdio_rx() -> bool { return is_rx_; } + void clear_sdio_data_flags() { sdio_.clear_multiple_interrupt_flags(clear_data_flags); } + void clear_sdio_cmd_flags() { sdio_.clear_multiple_interrupt_flags(clear_command_flags); } + void clear_sdio_common_flags() { sdio_.clear_multiple_interrupt_flags(clear_common_flags); } + auto get_state() -> Operational_State { return current_state_; } + void set_state(Operational_State state) { current_state_ = state; } + void set_transfer_error(SDIO_Error_Type error) { transfer_error_ = error; } + void set_transfer_end(bool end) { transfer_end_ = end; }; + + auto set_desired_clock(uint32_t desired_clock, bool wide_bus, bool low_power) -> SDIO_Error_Type { + sdio_.init(SDIO_Config{ + .desired_clock = desired_clock, + .enable_bypass = false, + .enable_powersave = low_power, + .enable_hwclock = false, + .clock_edge = Clock_Edge::RISING_EDGE, + .width = wide_bus ? Bus_Width::WIDTH_4BIT : Bus_Width::WIDTH_1BIT + }); + + sync_domains(); + desired_clock_ = desired_clock; + + return SDIO_Error_Type::OK; + } + +private: + CardDMA(); + + // Prevent copying or assigning + CardDMA(const CardDMA&) = delete; + auto operator=(const CardDMA&) -> CardDMA& = delete; + + // Helper function + auto wait_for_card_ready() -> SDIO_Error_Type; + + // Member variables + alignas(4) uint32_t sdcard_csd_[4]; + alignas(4) uint32_t sdcard_cid_[4]; + alignas(4) uint32_t sdcard_scr_[2]; + uint32_t desired_clock_; + uint32_t total_bytes_; + SDIO& sdio_; + SDIO_Config& config_; + const dma::DMA_Base dmaBase_; + const dma::DMA_Channel dmaChannel_; + dma::DMA& dma_; + uint16_t sdcard_rca_; + SDIO_Error_Type transfer_error_; + Interface_Version interface_version_; + Card_Type card_type_; + Operational_State current_state_; + bool transfer_end_; + bool multiblock_; + bool is_rx_; + + // Private helper methods + auto validate_voltage() -> SDIO_Error_Type; + auto get_command_sent_result() -> SDIO_Error_Type; + auto get_r1_result(Command_Index index) -> SDIO_Error_Type; + auto get_r6_result(Command_Index index, uint16_t* rca) -> SDIO_Error_Type; + auto get_r7_result() -> SDIO_Error_Type { return check_sdio_status(Command_Index::INVALID, false, false); }; + void sync_domains() { delayMicroseconds(8); } + + auto validate_transfer_params(uint32_t* buf, uint16_t size) -> bool { + if (buf == nullptr) return false; + // Size must be > 0, <= 2048 and power of 2 + return size > 0U && size <= 2048U && !(size & (size - 1U)); + } + + void process_sdsc_specific_csd(Card_Info* info, const uint8_t* csd_bytes) { + const uint32_t device_size = ((csd_bytes[6] & 0x3U) << 10) | + (csd_bytes[7] << 2) | + ((csd_bytes[8] >> 6) & 0x3U); + + const uint8_t device_size_multiplier = ((csd_bytes[9] & 0x3U) << 1) | + ((csd_bytes[10] >> 7) & 0x1U); + + // Store calculated values + info->csd.device_size = device_size; + info->csd.device_size_multiplier = device_size_multiplier; + + // Calculate block size and capacity + info->block_size = 1U << info->csd.read_block_length; + info->capacity = (device_size + 1U) * + (1U << (device_size_multiplier + 2U)) * + info->block_size; + } + + void process_sdhc_specific_csd(Card_Info* info, const uint8_t* csd_bytes) { + info->csd.device_size = static_cast((csd_bytes[7] & 0x3FU) << 16) | + static_cast((csd_bytes[8]) << 8) | + static_cast(csd_bytes[9]); + + // Set block size and calculate capacity + info->block_size = BLOCK_SIZE; + info->capacity = static_cast((info->csd.device_size + 1U) * + BLOCK_SIZE * KILOBYTE); + } + + void process_common_csd_tail(Card_Info* info, const uint8_t* csd_bytes) { + // Calculate sector_size + info->csd.sector_size = static_cast(((csd_bytes[9] & 0x3FU) << 1) | + (csd_bytes[10] & 0x80U) >> 7); + + // Calculate speed_factor and write_block_length + info->csd.speed_factor = static_cast((csd_bytes[11] & 0x1CU) >> 2); + info->csd.write_block_length = static_cast(((csd_bytes[11] & 0x3U) << 2) | + ((csd_bytes[12] & 0xC0U) >> 6)); + + // Calculate checksum + info->csd.checksum = static_cast((csd_bytes[15] & 0xFEU) >> 1); + } + + void disable_all_interrupts() { + sdio_.set_interrupt_enable(Interrupt_Type::DTCRCERRIE, false); + sdio_.set_interrupt_enable(Interrupt_Type::DTTMOUTIE, false); + sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, false); + sdio_.set_interrupt_enable(Interrupt_Type::STBITEIE, false); + sdio_.set_interrupt_enable(Interrupt_Type::TFHIE, false); + sdio_.set_interrupt_enable(Interrupt_Type::RFHIE, false); + sdio_.set_interrupt_enable(Interrupt_Type::TXUREIE, false); + sdio_.set_interrupt_enable(Interrupt_Type::RXOREIE, false); + } + + template + auto send_command_and_check(Command_Index command, uint32_t argument, + Command_Response response, Wait_Type type, CheckFunc check_result) -> SDIO_Error_Type { + sdio_.set_command_state_machine(command, argument, response, type); + sync_domains(); + sdio_.set_command_state_machine_enable(true); + return check_result(); + } +}; + +} // namespace sdio + +extern sdio::CardDMA& CardDMA_I; diff --git a/Marlin/src/HAL/GD32_MFL/sd/sdio.cpp b/Marlin/src/HAL/GD32_MFL/sd/sdio.cpp new file mode 100644 index 0000000000..a474c1977e --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/sd/sdio.cpp @@ -0,0 +1,231 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ARDUINO_ARCH_MFL + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(ONBOARD_SDIO) + +#include +#include +#include "SDCard.h" +#include "sdio.h" + +using namespace sdio; + +#define TARGET_CLOCK 6000000U +#define BLOCK_SIZE 512U +#define CARD_TIMEOUT 500 // ms +#define READ_RETRIES 3U + +inline constexpr uint32_t TARGET_SDIO_CLOCK = TARGET_CLOCK; +inline constexpr uint32_t SDIO_BLOCK_SIZE = BLOCK_SIZE; +inline constexpr uint32_t SD_TIMEOUT = CARD_TIMEOUT; +inline constexpr uint8_t SDIO_READ_RETRIES = READ_RETRIES; + +Card_State cardState = Card_State::READY; + +auto SDIO_SetBusWidth(Bus_Width width) -> bool { + return (CardDMA_I.set_hardware_bus_width(width) == SDIO_Error_Type::OK); +} + +void mfl_sdio_init() { + pinOpsPinout(SD_CMD_PinOps, static_cast(SDIO_CMD_PIN)); + pinOpsPinout(SD_CK_PinOps, static_cast(SDIO_CK_PIN)); + pinOpsPinout(SD_DATA0_PinOps, static_cast(SDIO_D0_PIN)); + pinOpsPinout(SD_DATA1_PinOps, static_cast(SDIO_D1_PIN)); + pinOpsPinout(SD_DATA2_PinOps, static_cast(SDIO_D2_PIN)); + pinOpsPinout(SD_DATA3_PinOps, static_cast(SDIO_D3_PIN)); + + NVIC_EnableIRQ(DMA1_Channel3_4_IRQn); + NVIC_EnableIRQ(SDIO_IRQn); +} + +bool SDIO_Init() { + SDIO_Error_Type result = SDIO_Error_Type::OK; + uint8_t retryCount = SDIO_READ_RETRIES; + + mfl_sdio_init(); + + uint8_t retries = retryCount; + for (;;) { + hal.watchdog_refresh(); + result = CardDMA_I.init(); + if (result == SDIO_Error_Type::OK) break; + if (!--retries) return false; + } + + CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, false, false); + + retries = retryCount; + for (;;) { + hal.watchdog_refresh(); + if (SDIO_SetBusWidth(Bus_Width::WIDTH_4BIT)) break; + if (!--retries) break; + } + + CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, true, true); + + // Fallback + if (!retries) { + mfl_sdio_init(); + retries = retryCount; + for (;;) { + hal.watchdog_refresh(); + result = CardDMA_I.init(); + if (result == SDIO_Error_Type::OK) break; + if (!--retries) return false; + } + CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, false, true); + } + + return true; +} + +static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t* src, uint8_t* dst) { + hal.watchdog_refresh(); + SDIO_Error_Type result = SDIO_Error_Type::OK; + + // Write + if (src) { + result = CardDMA_I.write(reinterpret_cast(const_cast(src)), block, 1); + } + // Read + else { + result = CardDMA_I.read(dst, block, 1); + } + + if (result != SDIO_Error_Type::OK) { + return false; + } + + millis_t timeout = millis() + SD_TIMEOUT; + while (CardDMA_I.get_state() != sdio::Operational_State::READY) { + if (ELAPSED(millis(), timeout)) { + return false; + } + } + + CardDMA_I.check_dma_complete(); + + timeout = millis() + SD_TIMEOUT; + do { + result = CardDMA_I.get_card_state(&cardState); + if (ELAPSED(millis(), timeout)) { + return false; + } + } while (result == SDIO_Error_Type::OK && cardState != sdio::Card_State::TRANSFER); + + return true; +} + +bool SDIO_ReadBlock(uint32_t block, uint8_t* dst) { + // Check if the address is aligned to 4 bytes + if (reinterpret_cast(dst) & 0x03) { + return false; + } + + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) { + if (SDIO_ReadWriteBlock_DMA(block, nullptr, dst)) { + return true; + } + } + + return false; +} + +bool SDIO_WriteBlock(uint32_t block, const uint8_t* src) { + // Check if the address is aligned to 4 bytes + if (reinterpret_cast(src) & 0x03) { + return false; + } + + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) { + if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) { + return true; + delay(10); + } + } + + return false; +} + +bool SDIO_IsReady() { + return (CardDMA_I.get_state() == sdio::Operational_State::READY); +} + +uint32_t SDIO_GetCardSize() { + return CardDMA_I.get_card_capacity(); +} + +// DMA interrupt handler +void DMA1_IRQHandler() { + auto& dma_instance = CardDMA_I.get_dma_instance(); + bool is_receive = CardDMA_I.get_is_sdio_rx(); + + // Check for Transfer Complete Interrupt + if (dma_instance.get_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_FTFIF)) { + dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_FTFIE, false); + dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_ERRIE, false); + dma_instance.clear_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_FTFIF); + if (is_receive) { + CardDMA_I.set_sdio_dma_enable(false); + CardDMA_I.clear_sdio_data_flags(); + CardDMA_I.set_state(sdio::Operational_State::READY); + } else { + CardDMA_I.set_data_end_interrupt(); + } + // Signal that transfer is complete + CardDMA_I.set_transfer_end(true); + } + + else if (dma_instance.get_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_ERRIF)) { + dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_HTFIE, false); + dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_ERRIE, false); + dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_FTFIE, false); + // Clear all flags + dma_instance.clear_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_GIF); + // Signal that an error occurred + CardDMA_I.set_transfer_error(SDIO_Error_Type::ERROR); + CardDMA_I.set_state(sdio::Operational_State::READY); + } +} + +extern "C" { + + void SDIO_IRQHandler(void) { + CardDMA_I.handle_interrupts(); + } + + void DMA1_Channel3_4_IRQHandler(void) { + DMA1_IRQHandler(); + } + +} // extern "C" + +#endif // ONBOARD_SDIO +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/sd/sdio.h b/Marlin/src/HAL/GD32_MFL/sd/sdio.h new file mode 100644 index 0000000000..a39e8c7a66 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/sd/sdio.h @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include +#include + +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 + +void sdio_mfl_init(); +auto SDIO_SetBusWidth(sdio::Bus_Width width) -> bool; +void DMA1_IRQHandler(dma::DMA_Channel channel); diff --git a/Marlin/src/HAL/GD32_MFL/spi_pins.h b/Marlin/src/HAL/GD32_MFL/spi_pins.h new file mode 100644 index 0000000000..c8a5836838 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/spi_pins.h @@ -0,0 +1,32 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ +#pragma once + +// Define SPI Pins: SCK, MISO, MOSI +#ifndef SD_SCK_PIN + #define SD_SCK_PIN PIN_SPI_SCK +#endif +#ifndef SD_MISO_PIN + #define SD_MISO_PIN PIN_SPI_MISO +#endif +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN PIN_SPI_MOSI +#endif diff --git a/Marlin/src/HAL/GD32_MFL/temp_soc.h b/Marlin/src/HAL/GD32_MFL/temp_soc.h new file mode 100644 index 0000000000..bd78fba5b9 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/temp_soc.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define TS_TYPICAL_V 1.405 +#define TS_TYPICAL_TEMP 25 +#define TS_TYPICAL_SLOPE 4.5 + +// TODO: Implement voltage scaling (calibrated Vrefint) and ADC resolution scaling (when applicable) +#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) * 0.001f)) / ((TS_TYPICAL_SLOPE) * 0.001f) + TS_TYPICAL_TEMP) diff --git a/Marlin/src/HAL/GD32_MFL/timers.cpp b/Marlin/src/HAL/GD32_MFL/timers.cpp new file mode 100644 index 0000000000..3bcfdd464b --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/timers.cpp @@ -0,0 +1,237 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 ARDUINO_ARCH_MFL + +#include "../../inc/MarlinConfig.h" +#include "timers.h" + +// ------------------------ +// Local defines +// ------------------------ + +#define SWSERIAL_TIMER_IRQ_PRIORITY_DEFAULT 1 // Requires tight bit timing to communicate reliably with TMC drivers +#define SERVO_TIMER_IRQ_PRIORITY_DEFAULT 1 // Requires tight PWM timing to control a BLTouch reliably +#define STEP_TIMER_IRQ_PRIORITY_DEFAULT 2 +#define TEMP_TIMER_IRQ_PRIORITY_DEFAULT 14 // Low priority avoids interference with other hardware and timers + +#ifndef TIMER_IRQ_PRIORITY + #define TIMER_IRQ_PRIORITY 12 +#endif + +#ifndef STEP_TIMER_IRQ_PRIORITY + #define STEP_TIMER_IRQ_PRIORITY STEP_TIMER_IRQ_PRIORITY_DEFAULT +#endif + +#ifndef TEMP_TIMER_IRQ_PRIORITY + #define TEMP_TIMER_IRQ_PRIORITY TEMP_TIMER_IRQ_PRIORITY_DEFAULT +#endif + +#if HAS_TMC_SW_SERIAL + #include + #ifndef SWSERIAL_TIMER_IRQ_PRIORITY + #define SWSERIAL_TIMER_IRQ_PRIORITY SWSERIAL_TIMER_IRQ_PRIORITY_DEFAULT + #endif +#endif + +#if HAS_SERVOS + #include "Servo.h" + #ifndef SERVO_TIMER_IRQ_PRIORITY + #define SERVO_TIMER_IRQ_PRIORITY SERVO_TIMER_IRQ_PRIORITY_DEFAULT + #endif +#endif + +#if ENABLED(SPEAKER) + // The MFL framework default timer priority is 12. The TEMP timer must have lower priority + // than this due to the long running temperature ISR, and STEP timer should higher priority. + #if !(TIMER_IRQ_PRIORITY > STEP_TIMER_IRQ_PRIORITY && TIMER_IRQ_PRIORITY < TEMP_TIMER_IRQ_PRIORITY) + #error "Default timer interrupt priority is unspecified or set to a value which may degrade performance." + #endif +#endif + +#ifndef STEP_TIMER + #define STEP_TIMER MF_TIMER_STEP +#endif +#ifndef TEMP_TIMER + #define TEMP_TIMER MF_TIMER_TEMP +#endif + +GeneralTimer& Step_Timer = GeneralTimer::get_instance(static_cast(STEP_TIMER)); +GeneralTimer& Temp_Timer = GeneralTimer::get_instance(static_cast(TEMP_TIMER)); + +bool is_step_timer_initialized = false; +bool is_temp_timer_initialized = false; + +// ------------------------ +// Public functions +// ------------------------ + +// Retrieves the clock frequency of the stepper timer +uint32_t GetStepperTimerClkFreq() { + // Cache result + static uint32_t clkFreq = Step_Timer.getTimerClockFrequency(); + return clkFreq; +} + +/** + * @brief Starts a hardware timer + * + * If the timer is not already initialized, this function will initialize it with the given frequency. + * The timer is started immediately after initialization + * + * @param timer The timer base index to start + * @param frequency The frequency at which the timer should run + * @return None + */ +void HAL_timer_start(const uint8_t timer_number, const uint32_t frequency) { + if (HAL_timer_initialized(timer_number) || (timer_number != MF_TIMER_STEP && timer_number != MF_TIMER_TEMP)) + return; + + const bool is_step = (timer_number == MF_TIMER_STEP); + const uint8_t priority = is_step ? + static_cast(STEP_TIMER_IRQ_PRIORITY) : + static_cast(TEMP_TIMER_IRQ_PRIORITY); + + // Get the reference of the timer instance + GeneralTimer& timer = is_step ? Step_Timer : Temp_Timer; + + if (is_step) { + timer.setPrescaler(STEPPER_TIMER_PRESCALE); + timer.setRolloverValue( + _MIN(HAL_TIMER_TYPE_MAX, hal_timer_t((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE))), + TimerFormat::TICK + ); + is_step_timer_initialized = true; + } + else { + timer.setRolloverValue(frequency, TimerFormat::HERTZ); + is_temp_timer_initialized = true; + } + + timer.setAutoReloadEnable(false); + timer.setInterruptPriority(priority, 0U); + HAL_timer_enable_interrupt(timer_number); + timer.start(); +} + +/** + * @brief Enables the interrupt for the specified timer + * + * @param handle The timer handle for which to enable the interrupt + * @return None + */ +void HAL_timer_enable_interrupt(const uint8_t timer_number) { + if (!HAL_timer_initialized(timer_number)) return; + + GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer; + + if (timer_number == MF_TIMER_STEP && !timer.hasInterrupt()) + timer.attachInterrupt(Step_Handler); + else if (timer_number == MF_TIMER_TEMP && !timer.hasInterrupt()) + timer.attachInterrupt(Temp_Handler); +} + +/** + * @brief Disables the interrupt for the specified timer + * + * @param handle The timer handle for which to disable the interrupt + * @return None + */ +void HAL_timer_disable_interrupt(const uint8_t timer_number) { + if (!HAL_timer_initialized(timer_number)) return; + + GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer; + if (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP) + timer.detachInterrupt(); +} + +/** + * @brief Checks if the interrupt is enabled for the specified timer + * + * @param handle The timer handle to check + * @return True if the interrupt is enabled, false otherwise + */ +bool HAL_timer_interrupt_enabled(const uint8_t timer_number) { + if (!HAL_timer_initialized(timer_number)) return false; + + GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer; + return (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP) + ? timer.hasInterrupt() + : false; +} + +// Sets the interrupt priorities for timers used by TMC SW serial and servos. +void SetTimerInterruptPriorities() { + TERN_(HAS_TMC_SW_SERIAL, SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIORITY, 0)); + TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIORITY, 0)); +} + +// ------------------------ +// Detect timer conflicts +// ------------------------ + +TERN_(HAS_TMC_SW_SERIAL, static constexpr timer::TIMER_Base timer_serial[] = {static_cast(TIMER_SERIAL)}); +TERN_(SPEAKER, static constexpr timer::TIMER_Base timer_tone[] = {static_cast(TIMER_TONE)}); +TERN_(HAS_SERVOS, static constexpr timer::TIMER_Base timer_servo[] = {static_cast(TIMER_SERVO)}); + +enum TimerPurpose { + PURPOSE_SERIAL, + PURPOSE_TONE, + PURPOSE_SERVO, + PURPOSE_STEP, + PURPOSE_TEMP +}; + +// List of timers to check for conflicts +// Includes the timer purpose to ease debugging when evaluating at build-time +// This cannot yet account for timers used for PWM output, such as for fans +static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = { + #if HAS_TMC_SW_SERIAL + { PURPOSE_SERIAL, timer_base_to_index(timer_serial[0]) }, // Set in variant.h + #endif + #if ENABLED(SPEAKER) + { PURPOSE_TONE, timer_base_to_index(timer_tone[0]) }, // Set in variant.h + #endif + #if HAS_SERVOS + { PURPOSE_SERVO, timer_base_to_index(timer_servo[0]) }, // Set in variant.h + #endif + { PURPOSE_STEP, MF_TIMER_STEP }, + { PURPOSE_TEMP, MF_TIMER_TEMP }, +}; + +// Verifies if there are any timer conflicts in the timers_in_use array +static constexpr bool verify_no_timer_conflicts() { + for (uint8_t i = 0; i < COUNT(timers_in_use); i++) + for (uint8_t j = i + 1; j < COUNT(timers_in_use); j++) + if (timers_in_use[i].t == timers_in_use[j].t) + return false; + + return true; +} + +// If this assertion fails at compile time, review the timers_in_use array. +// If default_envs is defined properly in platformio.ini, VSCode can evaluate the array +// when hovering over it, making it easy to identify the conflicting timers +static_assert(verify_no_timer_conflicts(), "One or more timer conflict detected. Examine \"timers_in_use\" to help identify conflict."); + +#endif // ARDUINO_ARCH_MFL diff --git a/Marlin/src/HAL/GD32_MFL/timers.h b/Marlin/src/HAL/GD32_MFL/timers.h new file mode 100644 index 0000000000..8aff77aa96 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/timers.h @@ -0,0 +1,149 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../inc/MarlinConfig.h" + +#include + +// ------------------------ +// Defines +// ------------------------ + +// Timer instance definitions +#define MF_TIMER_STEP 3 +#define MF_TIMER_TEMP 1 +#define MF_TIMER_PULSE MF_TIMER_STEP + +typedef uint32_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) + +#ifndef HAL_TIMER_RATE + extern uint32_t GetStepperTimerClkFreq(); + #define HAL_TIMER_RATE GetStepperTimerClkFreq() +#endif + +// Timer configuration constants +#define STEPPER_TIMER_RATE 2000000 +#define TEMP_TIMER_FREQUENCY 1000 + +// Timer prescaler calculations +#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE)) // Prescaler = 30 +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs + +// Pulse Timer (counter) calculations +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE + +// Timer interrupt priorities +#define STEP_TIMER_IRQ_PRIORITY 2 +#define TEMP_TIMER_IRQ_PRIORITY 14 + +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) + +extern void Step_Handler(); +extern void Temp_Handler(); + +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() void Step_Handler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() void Temp_Handler() +#endif + +extern GeneralTimer& Step_Timer; +extern GeneralTimer& Temp_Timer; + +extern bool is_step_timer_initialized; +extern bool is_temp_timer_initialized; + +// Build-time mapping between timer base and index. Used in timers.cpp and fast_pwm.cpp +static inline constexpr struct {timer::TIMER_Base base; uint8_t timer_number;} base_to_index[] = { + { timer::TIMER_Base::TIMER0_BASE, 0 }, + { timer::TIMER_Base::TIMER1_BASE, 1 }, + { timer::TIMER_Base::TIMER2_BASE, 2 }, + { timer::TIMER_Base::TIMER3_BASE, 3 }, + { timer::TIMER_Base::TIMER4_BASE, 4 }, + { timer::TIMER_Base::TIMER5_BASE, 5 }, + { timer::TIMER_Base::TIMER6_BASE, 6 }, + { timer::TIMER_Base::TIMER7_BASE, 7 } +}; + +// Converts a timer base to an integer timer index. +constexpr auto timer_base_to_index(timer::TIMER_Base base) -> int { + for (const auto& timer : base_to_index) { + if (timer.base == base) { + return static_cast(timer.timer_number); + } + } + return -1; +} + +// ------------------------ +// Public functions +// ------------------------ + +void HAL_timer_start(const uint8_t timer, const uint32_t frequency); +void HAL_timer_enable_interrupt(const uint8_t timer); +void HAL_timer_disable_interrupt(const uint8_t timer); +bool HAL_timer_interrupt_enabled(const uint8_t timer); + +// Configure timer priorities for peripherals such as Software Serial or Servos. +// Exposed here to allow all timer priority information to reside in timers.cpp +void SetTimerInterruptPriorities(); + +// FORCE_INLINE because these are used in performance-critical situations +FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_number) { + return (timer_number == MF_TIMER_STEP) ? is_step_timer_initialized : + (timer_number == MF_TIMER_TEMP) ? is_temp_timer_initialized : + false; +} + +FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_number) { + if (!HAL_timer_initialized(timer_number)) return 0U; + + GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer; + + return (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP) + ? timer.getCounter(TimerFormat::TICK) + : 0U; +} + +FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_number, const hal_timer_t value) { + if (!HAL_timer_initialized(timer_number)) return; + + const auto new_value = static_cast(value + 1U); + GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer; + + if (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP) { + timer.setRolloverValue(new_value, TimerFormat::TICK); + if (value < static_cast(timer.getCounter(TimerFormat::TICK))) + timer.refresh(); + } +} + +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/GD32_MFL/u8g/LCD_defines.h b/Marlin/src/HAL/GD32_MFL/u8g/LCD_defines.h new file mode 100644 index 0000000000..720d958779 --- /dev/null +++ b/Marlin/src/HAL/GD32_MFL/u8g/LCD_defines.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +// MFL LCD-specific defines +uint8_t u8g_com_HAL_MFL_sw_spi_fn(u8g_t* u8g, uint8_t msg, uint8_t arg_val, void* arg_ptr); // u8g_com_mfl_swspi.cpp +#define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_MFL_sw_spi_fn diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index 5186578019..a211dfe259 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -27,7 +27,7 @@ #define GCC_VERSION (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) #endif -#include HAL_PATH(.,HAL.h) +#include HAL_PATH(.., HAL.h) extern MarlinHAL hal; #define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION) diff --git a/Marlin/src/HAL/HC32/HAL.cpp b/Marlin/src/HAL/HC32/HAL.cpp new file mode 100644 index 0000000000..a74d21e6fd --- /dev/null +++ b/Marlin/src/HAL/HC32/HAL.cpp @@ -0,0 +1,56 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "HAL.h" +#include +#include + +// +// Emergency Parser +// +#if ENABLED(EMERGENCY_PARSER) + +extern "C" void core_hook_usart_rx_irq(uint8_t ch, uint8_t usart) { + // Only handle receive on host serial ports + if (false + #ifdef SERIAL_PORT + || usart != SERIAL_PORT + #endif + #ifdef SERIAL_PORT_2 + || usart != SERIAL_PORT_2 + #endif + #ifdef SERIAL_PORT_3 + || usart != SERIAL_PORT_3 + #endif + ) { + return; + } + + // Submit character to emergency parser + if (MYSERIAL1.emergency_parser_enabled()) + emergency_parser.update(MYSERIAL1.emergency_state, ch); +} + +#endif // EMERGENCY_PARSER +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/HAL.h b/Marlin/src/HAL/HC32/HAL.h new file mode 100644 index 0000000000..f751dea091 --- /dev/null +++ b/Marlin/src/HAL/HC32/HAL.h @@ -0,0 +1,119 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * HAL for HC32F460 based boards + * + * Note: MarlinHAL class is in MarlinHAL.h/cpp + */ + +#define CPU_32_BIT + +#include "../../inc/MarlinConfig.h" + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" + +#include "fastio.h" +#include "timers.h" + +// +// Serial Ports +// + +#include "MarlinSerial.h" + +// +// Emergency Parser +// +#if ENABLED(EMERGENCY_PARSER) + extern "C" void usart_rx_irq_hook(uint8_t ch, uint8_t usart); +#endif + +// +// Misc. Defines +// +#define square(x) ((x) * (x)) + +#ifndef strncpy_P + #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) +#endif + +// +// Misc. Functions +// +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) pin_t(p) +#endif + +#define CRITICAL_SECTION_START() \ + const bool irqon = !__get_PRIMASK(); \ + __disable_irq(); \ + __DSB(); +#define CRITICAL_SECTION_END() \ + __DSB(); \ + if (irqon) __enable_irq(); + +#define cli() __disable_irq() +#define sei() __enable_irq() + +// bss_end alias +#define __bss_end __bss_end__ + +// Fix bug in pgm_read_ptr +#undef pgm_read_ptr +#define pgm_read_ptr(addr) (*(addr)) + +// +// ADC +// +#define HAL_ADC_VREF_MV 3300 +#define HAL_ADC_RESOLUTION 12 + +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + +// +// Debug port disable +// JTMS / SWDIO = PA13 +// JTCK / SWCLK = PA14 +// JTDI = PA15 +// JTDO = PB3 +// NJTRST = PB4 +// +#define DBG_SWCLK _BV(0) +#define DBG_SWDIO _BV(1) +#define DBG_TDO _BV(2) +#define DBG_TDI _BV(3) +#define DBG_TRST _BV(4) +#define DBG_ALL (DBG_SWCLK | DBG_SWDIO | DBG_TDO | DBG_TDI | DBG_TRST) + +#define JTAGSWD_RESET() PORT_DebugPortSetting(DBG_ALL, Enable); +#define JTAG_DISABLE() PORT_DebugPortSetting(DBG_TDO | DBG_TDI | DBG_TRST, Disable); +#define JTAGSWD_DISABLE() PORT_DebugPortSetting(DBG_ALL, Disable); + +// +// MarlinHAL implementation +// +#include "MarlinHAL.h" diff --git a/Marlin/src/HAL/HC32/MarlinHAL.cpp b/Marlin/src/HAL/HC32/MarlinHAL.cpp new file mode 100644 index 0000000000..f1d85f1694 --- /dev/null +++ b/Marlin/src/HAL/HC32/MarlinHAL.cpp @@ -0,0 +1,309 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * HAL for HC32F460, based heavily on the legacy implementation and STM32F1 + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" + +#include "HAL.h" // Includes MarlinHAL.h +#include +#include + +#if TEMP_SENSOR_SOC + #include +#endif + +extern "C" char *_sbrk(int incr); + +#if ENABLED(POSTMORTEM_DEBUGGING) + // From MinSerial.cpp + extern void install_min_serial(); +#endif + +#if ENABLED(MARLIN_DEV_MODE) + inline void HAL_clock_frequencies_dump() { + // 1. dump all clock frequencies + update_system_clock_frequencies(); + SERIAL_ECHOPGM( + "-- clocks dump -- \nSYS=", SYSTEM_CLOCK_FREQUENCIES.system, + "\nHCLK=", SYSTEM_CLOCK_FREQUENCIES.hclk, + "\nPCLK0=", SYSTEM_CLOCK_FREQUENCIES.pclk0, + "\nPCLK1=", SYSTEM_CLOCK_FREQUENCIES.pclk1, + "\nPCLK2=", SYSTEM_CLOCK_FREQUENCIES.pclk2, + "\nPCLK3=", SYSTEM_CLOCK_FREQUENCIES.pclk3, + "\nPCLK4=", SYSTEM_CLOCK_FREQUENCIES.pclk4, + "\nEXCLK=", SYSTEM_CLOCK_FREQUENCIES.exclk, + "\nF_CPU=", F_CPU + ); + + // 2. dump current system clock source + en_clk_sys_source_t clkSrc = CLK_GetSysClkSource(); + SERIAL_ECHOPGM("\nSYSCLK="); + switch (clkSrc) { + case ClkSysSrcHRC: SERIAL_ECHOPGM("HRC"); break; + case ClkSysSrcMRC: SERIAL_ECHOPGM("MRC"); break; + case ClkSysSrcLRC: SERIAL_ECHOPGM("LRC"); break; + case ClkSysSrcXTAL: SERIAL_ECHOPGM("XTAL"); break; + case ClkSysSrcXTAL32: SERIAL_ECHOPGM("XTAL32"); break; + case CLKSysSrcMPLL: SERIAL_ECHOPGM("MPLL"); + + // 3. if MPLL is used, dump MPLL settings: + // (derived from CLK_SetPllSource and CLK_MpllConfig) + // source + switch (M4_SYSREG->CMU_PLLCFGR_f.PLLSRC) { + case ClkPllSrcXTAL: SERIAL_ECHOPGM(",XTAL"); break; + case ClkPllSrcHRC: SERIAL_ECHOPGM(",HRC"); break; + default: break; + } + + // PLL multipliers and dividers + SERIAL_ECHOPGM( + "\nP=", M4_SYSREG->CMU_PLLCFGR_f.MPLLP + 1UL, + "\nQ=", M4_SYSREG->CMU_PLLCFGR_f.MPLLQ + 1UL, + "\nR=", M4_SYSREG->CMU_PLLCFGR_f.MPLLR + 1UL, + "\nN=", M4_SYSREG->CMU_PLLCFGR_f.MPLLN + 1UL, + "\nM=", M4_SYSREG->CMU_PLLCFGR_f.MPLLM + 1UL + ); + break; + default: break; + } + + // Done + SERIAL_ECHOPGM("\n--\n"); + } +#endif // MARLIN_DEV_MODE + +// +// MarlinHAL class implementation +// + +pin_t MarlinHAL::last_adc_pin; + +#if TEMP_SENSOR_SOC + float MarlinHAL::soc_temp = 0; +#endif + +MarlinHAL::MarlinHAL() {} + +void MarlinHAL::watchdog_init() { + TERN_(USE_WATCHDOG, WDT.begin(5000)); // Reset on 5 second timeout +} + +void MarlinHAL::watchdog_refresh() { + TERN_(USE_WATCHDOG, WDT.reload()); +} + +void MarlinHAL::init() { + NVIC_SetPriorityGrouping(0x3); + + // Print clock frequencies to host serial + TERN_(MARLIN_DEV_MODE, HAL_clock_frequencies_dump()); + + // Register min serial + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); + + // warn if low memory after init + if (freeMemory() < 1024) { + SERIAL_WARN_MSG("HAL: low memory after init!\n"); + } +} + +void MarlinHAL::init_board() {} + +void MarlinHAL::reboot() { + NVIC_SystemReset(); +} + +bool MarlinHAL::isr_state() { + return !__get_PRIMASK(); +} + +void MarlinHAL::isr_on() { + __enable_irq(); +} + +void MarlinHAL::isr_off() { + __disable_irq(); +} + +void MarlinHAL::delay_ms(const int ms) { + delay(ms); +} + +void MarlinHAL::idletask() { + #if ENABLED(MARLIN_DEV_MODE) + // check & print serial RX errors + MSerialT *serials[] = { &MSerial1, &MSerial2 }; + for (int serial = 0; serial < 2; serial++) { + usart_receive_error_t err = serials[serial]->getReceiveError(); + if (err != usart_receive_error_t::None) { + // "Warning: MSerial[n] RX [Framing|Parity|Overrun] Error" + SERIAL_WARN_START(); + SERIAL_ECHOPGM(" MSerial"); + SERIAL_ECHO(serial + 1); + SERIAL_ECHOPGM(" RX "); + switch(err) { + case usart_receive_error_t::FramingError: SERIAL_ECHOPGM("Framing"); break; + case usart_receive_error_t::ParityError: SERIAL_ECHOPGM("Parity"); break; + case usart_receive_error_t::OverrunError: SERIAL_ECHOPGM("Overrun"); break; + case usart_receive_error_t::RxDataDropped: SERIAL_ECHOPGM("DataDropped"); break; + default: break; + } + SERIAL_ECHOPGM(" Error"); + SERIAL_EOL(); + } + } + #endif +} + +uint8_t MarlinHAL::get_reset_source() { + // Query reset cause from RMU + stc_rmu_rstcause_t rstCause; + RMU_GetResetCause(&rstCause); + + // Map reset cause code to those expected by Marlin + // - Reset causes are flags, so multiple can be set + TERN_(MARLIN_DEV_MODE, printf("-- Reset Cause -- \n")); + uint8_t cause = 0; + #define MAP_CAUSE(from, to) \ + if (rstCause.from == Set) { \ + TERN_(MARLIN_DEV_MODE, printf(" - " STRINGIFY(from) "\n")); \ + cause |= to; \ + } + + // Power on + MAP_CAUSE(enPowerOn, RST_POWER_ON) // Power on reset + + // External + MAP_CAUSE(enRstPin, RST_EXTERNAL) // Reset pin + MAP_CAUSE(enPvd1, RST_EXTERNAL) // Program voltage detection reset + MAP_CAUSE(enPvd2, RST_EXTERNAL) // " + + // Brown out + MAP_CAUSE(enBrownOut, RST_BROWN_OUT) // Brown out reset + + // Wdt + MAP_CAUSE(enWdt, RST_WATCHDOG) // Watchdog reset + MAP_CAUSE(enSwdt, RST_WATCHDOG) // Special WDT reset + + // Software + MAP_CAUSE(enPowerDown, RST_SOFTWARE) // MCU power down (?) + MAP_CAUSE(enSoftware, RST_SOFTWARE) // Software reset (e.g. NVIC_SystemReset()) + + // Misc. + MAP_CAUSE(enMpuErr, RST_BACKUP) // MPU error + MAP_CAUSE(enRamParityErr, RST_BACKUP) // RAM parity error + MAP_CAUSE(enRamEcc, RST_BACKUP) // RAM ecc error + MAP_CAUSE(enClkFreqErr, RST_BACKUP) // Clock frequency failure + MAP_CAUSE(enXtalErr, RST_BACKUP) // XTAL failure + + #undef MAP_CAUSE + return cause; +} + +void MarlinHAL::clear_reset_source() { + RMU_ClrResetFlag(); +} + +int MarlinHAL::freeMemory() { + volatile char top; + return &top - _sbrk(0); +} + +void MarlinHAL::adc_init() { + analogReadResolution(HAL_ADC_RESOLUTION); +} + +void MarlinHAL::adc_enable(const pin_t pin) { + #if TEMP_SENSOR_SOC + if (pin == TEMP_SOC_PIN) { + // Start OTS, min. 1s between reads + ChipTemperature.begin(); + ChipTemperature.setMinimumReadDeltaMillis(1000); + return; + } + #endif + + // Just set pin mode to analog + pinMode(pin, INPUT_ANALOG); +} + +void MarlinHAL::adc_start(const pin_t pin) { + MarlinHAL::last_adc_pin = pin; + + #if TEMP_SENSOR_SOC + if (pin == TEMP_SOC_PIN) { + // Read OTS + float temp; + if (ChipTemperature.read(temp)) + MarlinHAL::soc_temp = temp; + return; + } + #endif + + CORE_ASSERT(IS_GPIO_PIN(pin), "adc_start: invalid pin") + + analogReadAsync(pin); +} + +bool MarlinHAL::adc_ready() { + #if TEMP_SENSOR_SOC + if (MarlinHAL::last_adc_pin == TEMP_SOC_PIN) return true; + #endif + + CORE_ASSERT(IS_GPIO_PIN(MarlinHAL::last_adc_pin), "adc_ready: invalid pin") + + return getAnalogReadComplete(MarlinHAL::last_adc_pin); +} + +uint16_t MarlinHAL::adc_value() { + #if TEMP_SENSOR_SOC + if (MarlinHAL::last_adc_pin == TEMP_SOC_PIN) + return OTS_FLOAT_TO_ADC_READING(MarlinHAL::soc_temp); + #endif + + // Read conversion result + CORE_ASSERT(IS_GPIO_PIN(MarlinHAL::last_adc_pin), "adc_value: invalid pin") + + return getAnalogReadValue(MarlinHAL::last_adc_pin); +} + +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale, const bool invert) { + // Invert value if requested + const uint16_t val = invert ? scale - value : value; + + // AnalogWrite the value, core handles the rest + // Pin mode should be set by Marlin by calling SET_PWM() before calling this function + analogWriteScaled(pin, val, scale); +} + +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { + // TODO set_pwm_frequency is not implemented yet + panic("set_pwm_frequency is not implemented yet\n"); +} + +void flashFirmware(const int16_t) { MarlinHAL::reboot(); } + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/MarlinHAL.h b/Marlin/src/HAL/HC32/MarlinHAL.h new file mode 100644 index 0000000000..ba3ac4c731 --- /dev/null +++ b/Marlin/src/HAL/HC32/MarlinHAL.h @@ -0,0 +1,133 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include +#include + +typedef gpio_pin_t pin_t; + +#if TEMP_SENSOR_SOC + /** + * Convert ots measurement float to uint16_t for adc_value() + * + * @note returns float as integer in degrees C * 10, if T > 0 + */ + #define OTS_FLOAT_TO_ADC_READING(T) ((T) > 0 ? ((uint16_t)((T) * 10.0f)) : 0) + + /** + * Convert adc_value() uint16_t to ots measurement float + * + * @note see OTS_FLOAT_TO_ADC_READING for inverse + * + * @note RAW is oversampled by OVERSAMPLENR, so we need to divide first + */ + #define TEMP_SOC_SENSOR(RAW) ((float)(((RAW) / OVERSAMPLENR) / 10)) +#endif + +/** + * HAL class for Marlin on HC32F460 + */ +class MarlinHAL { +public: + // 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(); // Restart the firmware from 0x0 + + // Interrupts + static bool isr_state(); + static void isr_on(); + static void isr_off(); + + static void delay_ms(const int ms); + + // Tasks, called from marlin.idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); + + // Free SRAM + static int freeMemory(); + + // + // ADC Methods + // + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given pin. Called from Temperature::isr! + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static bool adc_ready(); + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. + */ + static void set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale = 255, const bool invert = false); + + /** + * Set the frequency of the timer for the given pin. + * All Timer PWM pins run at the same frequency. + */ + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); + +private: + /** + * Pin number of the last pin that was used with adc_start() + */ + static pin_t last_adc_pin; + + #if TEMP_SENSOR_SOC + /** + * On-chip temperature sensor value + */ + static float soc_temp; + #endif +}; + +// M997: Trigger a firmware update from SD card (after upload). +// On HC32F460, a reboot is enough to do this. +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif + +void flashFirmware(const int16_t); diff --git a/Marlin/src/HAL/HC32/MarlinSerial.cpp b/Marlin/src/HAL/HC32/MarlinSerial.cpp new file mode 100644 index 0000000000..11d4abfab9 --- /dev/null +++ b/Marlin/src/HAL/HC32/MarlinSerial.cpp @@ -0,0 +1,162 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" +#include "MarlinSerial.h" +#include + +/** + * Not every MarlinSerial instance should handle emergency parsing, as + * it would not make sense to parse G-Code from TMC responses + */ +constexpr bool serial_handles_emergency(int port) { + return false + #ifdef SERIAL_PORT + || (SERIAL_PORT) == port + #endif + #ifdef SERIAL_PORT_2 + || (SERIAL_PORT_2) == port + #endif + #ifdef LCD_SERIAL_PORT + || (LCD_SERIAL_PORT) == port + #endif + ; +} + +// +// Define serial ports +// + +// serial port where RX and TX use IRQs +#define DEFINE_IRQ_SERIAL_MARLIN(name, n) \ + MSerialT name(serial_handles_emergency(n), \ + &USART##n##_config, \ + BOARD_USART##n##_TX_PIN, \ + BOARD_USART##n##_RX_PIN); + +// serial port where RX uses DMA and TX uses IRQs +// all serial ports use DMA1 +// since there are 4 USARTs and 4 DMA channels, we can use the USART number as the DMA channel +#define DEFINE_DMA_SERIAL_MARLIN(name, n) \ + MSerialT name(serial_handles_emergency(n), \ + &USART##n##_config, \ + BOARD_USART##n##_TX_PIN, \ + BOARD_USART##n##_RX_PIN, \ + M4_DMA1, \ + ((en_dma_channel_t)(n - 1))); // map USART1 to DMA channel 0, USART2 to DMA channel 1, etc. + +#define DEFINE_SERIAL_MARLIN(name, n) TERN(SERIAL_DMA, DEFINE_DMA_SERIAL_MARLIN(name, n), DEFINE_IRQ_SERIAL_MARLIN(name, n)) + +DEFINE_SERIAL_MARLIN(MSerial1, 1); +DEFINE_SERIAL_MARLIN(MSerial2, 2); + +// TODO: remove this warning when SERIAL_DMA has been tested some more +#if ENABLED(SERIAL_DMA) + #warning "SERIAL_DMA may be unstable on HC32F460." +#endif + +// +// Serial port assertions +// + +// Check the type of each serial port by passing it to a template function. +// HardwareSerial is known to sometimes hang the controller when an error occurs, +// so this case will fail the static assert. All other classes are assumed to be ok. +template +constexpr bool IsSerialClassAllowed(const T &) { return true; } +constexpr bool IsSerialClassAllowed(const HardwareSerial &) { return false; } +constexpr bool IsSerialClassAllowed(const Usart &) { return false; } + +// If you encounter this error, replace SerialX with MSerialX, for example MSerial3. +#define CHECK_CFG_SERIAL(A) static_assert(IsSerialClassAllowed(A), STRINGIFY(A) " is defined incorrectly"); +#define CHECK_AXIS_SERIAL(A) static_assert(IsSerialClassAllowed(A##_HARDWARE_SERIAL), STRINGIFY(A) "_HARDWARE_SERIAL must be defined in the form MSerial1, rather than Serial1"); + +// Non-TMC ports were already validated in HAL.h, so do not require verbose error messages. +#ifdef MYSERIAL1 + CHECK_CFG_SERIAL(MYSERIAL1); +#endif +#ifdef MYSERIAL2 + CHECK_CFG_SERIAL(MYSERIAL2); +#endif +#ifdef LCD_SERIAL + CHECK_CFG_SERIAL(LCD_SERIAL); +#endif +#if AXIS_HAS_HW_SERIAL(X) + CHECK_AXIS_SERIAL(X); +#endif +#if AXIS_HAS_HW_SERIAL(X2) + CHECK_AXIS_SERIAL(X2); +#endif +#if AXIS_HAS_HW_SERIAL(Y) + CHECK_AXIS_SERIAL(Y); +#endif +#if AXIS_HAS_HW_SERIAL(Y2) + CHECK_AXIS_SERIAL(Y2); +#endif +#if AXIS_HAS_HW_SERIAL(Z) + CHECK_AXIS_SERIAL(Z); +#endif +#if AXIS_HAS_HW_SERIAL(Z2) + CHECK_AXIS_SERIAL(Z2); +#endif +#if AXIS_HAS_HW_SERIAL(Z3) + CHECK_AXIS_SERIAL(Z3); +#endif +#if AXIS_HAS_HW_SERIAL(Z4) + CHECK_AXIS_SERIAL(Z4); +#endif +#if AXIS_HAS_HW_SERIAL(I) + CHECK_AXIS_SERIAL(I); +#endif +#if AXIS_HAS_HW_SERIAL(J) + CHECK_AXIS_SERIAL(J); +#endif +#if AXIS_HAS_HW_SERIAL(K) + CHECK_AXIS_SERIAL(K); +#endif +#if AXIS_HAS_HW_SERIAL(E0) + CHECK_AXIS_SERIAL(E0); +#endif +#if AXIS_HAS_HW_SERIAL(E1) + CHECK_AXIS_SERIAL(E1); +#endif +#if AXIS_HAS_HW_SERIAL(E2) + CHECK_AXIS_SERIAL(E2); +#endif +#if AXIS_HAS_HW_SERIAL(E3) + CHECK_AXIS_SERIAL(E3); +#endif +#if AXIS_HAS_HW_SERIAL(E4) + CHECK_AXIS_SERIAL(E4); +#endif +#if AXIS_HAS_HW_SERIAL(E5) + CHECK_AXIS_SERIAL(E5); +#endif +#if AXIS_HAS_HW_SERIAL(E6) + CHECK_AXIS_SERIAL(E6); +#endif +#if AXIS_HAS_HW_SERIAL(E7) + CHECK_AXIS_SERIAL(E7); +#endif + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/MarlinSerial.h b/Marlin/src/HAL/HC32/MarlinSerial.h new file mode 100644 index 0000000000..1a97805a51 --- /dev/null +++ b/Marlin/src/HAL/HC32/MarlinSerial.h @@ -0,0 +1,94 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../core/serial_hook.h" +#include + +#define SERIAL_INDEX_MIN 1 +#define SERIAL_INDEX_MAX 4 +#include "../shared/serial_ports.h" + +#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() +#endif + +// Optionally set uart IRQ priority to reduce overflow errors +//#define UART_RX_IRQ_PRIO 1 +//#define UART_TX_IRQ_PRIO 1 +//#define UART_RX_DMA_IRQ_PRIO 1 + +struct MarlinSerial : public Usart { + MarlinSerial( + struct usart_config_t *usart_device, + gpio_pin_t tx_pin, + gpio_pin_t rx_pin + #if ENABLED(SERIAL_DMA) + , M4_DMA_TypeDef *dma_unit = nullptr, + en_dma_channel_t rx_dma_channel = DmaCh0 + #endif + ) : Usart(usart_device, tx_pin, rx_pin) { + #if ENABLED(SERIAL_DMA) + if (dma_unit != nullptr) { + enableRxDma(dma_unit, rx_dma_channel); + } + #endif + } + + #if defined(UART_RX_IRQ_PRIO) || defined(UART_TX_IRQ_PRIO) || defined(UART_RX_DMA_IRQ_PRIO) + void setPriority() { + #if defined(UART_RX_IRQ_PRIO) + NVIC_SetPriority(c_dev()->interrupts.rx_data_available.interrupt_number, UART_RX_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.rx_error.interrupt_number, UART_RX_IRQ_PRIO); + #endif + + #if defined(UART_TX_IRQ_PRIO) + NVIC_SetPriority(c_dev()->interrupts.tx_buffer_empty.interrupt_number, UART_TX_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.tx_complete.interrupt_number, UART_TX_IRQ_PRIO); + #endif + + #if defined(UART_RX_DMA_IRQ_PRIO) && ENABLED(SERIAL_DMA) + NVIC_SetPriority(c_dev()->dma.rx.rx_data_available_dma_btc.interrupt_number, UART_RX_DMA_IRQ_PRIO); + #endif + } + + void begin(uint32_t baud) { + Usart::begin(baud); + setPriority(); + } + + void begin(uint32_t baud, uint8_t config) { + Usart::begin(baud, config); + setPriority(); + } + + void begin(uint32_t baud, const stc_usart_uart_init_t *config, const bool rxNoiseFilter = true) { + Usart::begin(baud, config, rxNoiseFilter); + setPriority(); + } + #endif // UART_RX_IRQ_PRIO || UART_TX_IRQ_PRIO || UART_RX_DMA_IRQ_PRIO +}; + +typedef Serial1Class MSerialT; + +extern MSerialT MSerial1; +extern MSerialT MSerial2; diff --git a/Marlin/src/HAL/HC32/MinSerial.cpp b/Marlin/src/HAL/HC32/MinSerial.cpp new file mode 100644 index 0000000000..93017ee0df --- /dev/null +++ b/Marlin/src/HAL/HC32/MinSerial.cpp @@ -0,0 +1,151 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" +#include + +#if ANY(POSTMORTEM_DEBUGGING, PANIC_ENABLE) + +#include + +// +// Shared by both panic and PostMortem debugging +// +static void minserial_begin() { + #if !WITHIN(SERIAL_PORT, 1, 3) + #warning "MinSerial requires a physical UART port for output." + #warning "Disabling MinSerial because the used serial port is not a HW port." + #else + + // Prepare usart_sync configuration + const stc_usart_uart_init_t usart_config = { + .enClkMode = UsartIntClkCkNoOutput, + .enClkDiv = UsartClkDiv_1, + .enDataLength = UsartDataBits8, + .enDirection = UsartDataLsbFirst, + .enStopBit = UsartOneStopBit, + .enParity = UsartParityNone, + .enSampleMode = UsartSampleBit8, + .enDetectMode = UsartStartBitFallEdge, + .enHwFlow = UsartRtsEnable, + }; + + // Initializes usart_sync driver + #define __USART_SYNC_INIT(port_no, baud, config) \ + usart_sync_init(M4_USART##port_no, \ + BOARD_USART##port_no##_TX_PIN, \ + baud, \ + config); + #define USART_SYNC_INIT(port_no, baud, config) __USART_SYNC_INIT(port_no, baud, config) + + // This will reset the baudrate to what is defined in Configuration.h, + // ignoring any changes made with e.g. M575. + // keeping the dynamic baudrate would require re-calculating the baudrate + // using the register values, which is a pain... + + // TODO: retain dynamic baudrate in MinSerial init + // -> see USART_SetBaudrate(), needs to be inverted + USART_SYNC_INIT(SERIAL_PORT, BAUDRATE, &usart_config); + + #undef USART_SYNC_INIT + #undef __USART_SYNC_INIT + #endif +} + +static void minserial_putc(char c) { + #if WITHIN(SERIAL_PORT, 1, 3) + #define __USART_SYNC_PUTC(port_no, ch) usart_sync_putc(M4_USART##port_no, ch); + #define USART_SYNC_PUTC(port_no, ch) __USART_SYNC_PUTC(port_no, ch) + + USART_SYNC_PUTC(SERIAL_PORT, c); + + #undef USART_SYNC_PUTC + #undef __USART_SYNC_PUTC + #endif +} + +// +// Panic only +// +#ifdef PANIC_ENABLE + +void panic_begin() { + minserial_begin(); + panic_puts("\n\nPANIC:\n"); +} + +void panic_puts(const char *str) { + while (*str) minserial_putc(*str++); +} + +#endif // PANIC_ENABLE + +// +// PostMortem debugging only +// +#if ENABLED(POSTMORTEM_DEBUGGING) + +#include "../shared/MinSerial.h" +#include + +void fault_handlers_init() { + // Enable cpu traps: + // - Divide by zero + // - Unaligned access + SCB->CCR |= SCB_CCR_DIV_0_TRP_Msk; //| SCB_CCR_UNALIGN_TRP_Msk; +} + +void install_min_serial() { + HAL_min_serial_init = &minserial_begin; + HAL_min_serial_out = &minserial_putc; +} + +extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__( + "b CommonHandler_ASM\n"); + } + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler(); +} + +#endif // POSTMORTEM_DEBUGGING +#endif // POSTMORTEM_DEBUGGING || PANIC_ENABLE + +// +// Panic_end is always required to print the '!!' to the host +// +void panic_end() { + // Print '!!' to signal error to host + // Do it 10x so it's not missed + for (uint_fast8_t i = 10; i--;) panic_printf("\n!!\n"); + + // Then, reset the board + NVIC_SystemReset(); +} + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/README.md b/Marlin/src/HAL/HC32/README.md new file mode 100644 index 0000000000..fe265dcf24 --- /dev/null +++ b/Marlin/src/HAL/HC32/README.md @@ -0,0 +1,107 @@ +# HC32F460 HAL + +This document provides notes on the HAL for the HC32F460 MCU. + +## Adding support for a new board + +The HC32F460 HAL is designed to be generic enough for any HC32F460-based board. Adding support for a new HC32F460-based board will require the following steps: + +1. Follow [the usual instructions](//marlinfw.org/docs/development/boards.html#adding-a-new-board) to add a new board to Marlin. (i.e., Add a pins file, edit `boards.h` and `pins.h`, etc.) +2. Determine the flash size your board uses: + - Examine the board's main processor. (Refer the naming key in `hc32.ini`.) + - Extend the `HC32F460C_common` base env for 256K, or `HC32F460E_common` for 512K. +3. Determine your board's application start address (see [below](#finding-the-application-start-address)) +4. Set `board_upload.offset_address` to the app start address once you've found it. If your board doesn't use a bootloader, you may be able to use the "ICSP" header or DFU. This document will be updated once we have more information about flashing without a bootloader. + +### Finding the application start address + +If the board contains a bootloader you'll need to find the application address. This is the address the bootloader jumps to after it's done. You can find this address in a few different ways: + +#### 1. Using log messages + +If you're lucky, the bootloader may print the app start address on the serial output during boot. To check for this, use your favorite serial monitor to observe the serial output when you power on the board. Look for a message like "Jumping to 0xC000" or "GotoApp->addr=0xC000". This line would be printed before Marlin's "start" message. + +Example: + +``` +[...] +version 1.2 +sdio init success! +Disk init +Tips ------ None Firmware file +GotoApp->addr=0xC000 + +start +[...] +``` + +#### 2. Using published source code + +If the vendor has published Marlin source code that includes the bootloader, you can search the bootloader source code for the address. Begin your search with the following steps: + +1. Find the code that sets the vector table offset + +The vector table offset is usually set using a line like this: + +```c +SCB->VTOR = ((uint32_t) APP_START_ADDRESS & SCB_VTOR_TBLOFF_Msk); +``` + +Just searching for `SCB->VTOR` should yield some results. From there, you just need to look at the value that's assigned to it. The example uses `APP_START_ADDRESS`. + +> [!NOTE] Some vendors publish incomplete source code. But they sometimes leave version control related files in the repo, which can contain previous version of files that were removed. Find these by including folders like `.git` or `.svn` in your search. + +> [!NOTE] The example is based on the [Voxelab-64/Aquila_X2](//github.com/Voxelab-64/Aquila_X2/blob/main/firmware/Sources/.svn/pristine/ec/ec82bcb480b511906bc3e6658450e3a803ab9813.svn-base#L96) which actually includes deleted files in its repo. + +2. Using a linker script + +If the repository contains a linker script, look at the memory regions, specifically a region named `FLASH` or similar. The `ORIGIN` of that region will be the application start address. + +**Example:** + +```ld +MEMORY +{ + FLASH (rx): ORIGIN = 0x0000C000, LENGTH = 512K + OTP (rx): ORIGIN = 0x03000C00, LENGTH = 1020 + RAM (rwx): ORIGIN = 0x1FFF8000, LENGTH = 188K + RET_RAM (rwx): ORIGIN = 0x200F0000, LENGTH = 4K +} +``` + +> [!NOTE] This example is based on [Voxelab-64/Aquila_X2](//github.com/Voxelab-64/Aquila_X2/blob/d1f23adf96920996b979bc31023d1dce236d05db/firmware/Sources/main/hdsc32core/hc32f46x_flash.ld#L55) + +## Documentation on the HC32F460 + +Due to uncertain licensing (w/r/t STMicro), documentation for the HC32F460 is only available upon request. Documentation includes the following: + +- Datasheet, user manual, reference manual +- Application notes for the DDL +- DDL source code +- IDE support packages (Keil, IAR, ...) including .svd files +- Programming software +- Emulator / debugger drivers +- Development board documentation and schematics +- Errata documents +- (Limited) sales information +- Full Voxelab firmware source code +- Documents in Chinese or English (machine translated) + +Contact me on Discord (@shadow578) if you need it. + +## Dependencies + +This HAL depends on the following projects: + +- [shadow578/platform-hc32f46x](//github.com/shadow578/platform-hc32f46x) (PlatformIO platform for HC32F46x) +- [shadow578/framework-arduino-hc32f46x](//github.com/shadow578/framework-arduino-hc32f46x) (Arduino framework for HC32F46x) +- [shadow578/framework-hc32f46x-ddl](//github.com/shadow578/framework-hc32f46x-ddl) (HC32F46x DDL framework) + +## Credits + +This HAL wouldn't be possible without the following projects: + +- [Voxelab-64/Aquila_X2](//github.com/Voxelab-64/Aquila_X2) (original implementation) +- [alexqzd/Marlin-H32](//github.com/alexqzd/Marlin-H32) (misc. fixes to the original implementation) +- [kgoveas/Arduino-Core-Template](//github.com/kgoveas/Arduino-Core-Template) (template for Arduino headers) +- [stm32duino/Arduino_Core_STM32](//github.com/stm32duino/Arduino_Core_STM32) (misc. Arduino functions) diff --git a/Marlin/src/HAL/HC32/Servo.cpp b/Marlin/src/HAL/HC32/Servo.cpp new file mode 100644 index 0000000000..ce78572ef5 --- /dev/null +++ b/Marlin/src/HAL/HC32/Servo.cpp @@ -0,0 +1,84 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" + +#if HAS_SERVOS + +#include "Servo.h" + +static uint8_t servoCount = 0; +static MarlinServo *servos[NUM_SERVOS] = {0}; + +constexpr uint32_t servoDelays[] = SERVO_DELAY; +static_assert(COUNT(servoDelays) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); + +// +// MarlinServo impl +// +MarlinServo::MarlinServo() { + this->channel = servoCount++; + servos[this->channel] = this; +} + +int8_t MarlinServo::attach(const pin_t apin) { + // Use last pin if pin not given + if (apin >= 0) this->pin = apin; + + // If attached, do nothing but no fail + if (this->servo.attached()) return 0; + + // Attach + const uint8_t rc = this->servo.attach(this->pin); + return rc == INVALID_SERVO ? -1 : rc; +} + +void MarlinServo::detach() { + this->servo.detach(); +} + +bool MarlinServo::attached() { + return this->servo.attached(); +} + +void MarlinServo::write(servo_angle_t angle) { + this->angle = angle; + this->servo.write(angle); +} + +void MarlinServo::move(servo_angle_t angle) { + // Attach with pin=-1 to use last pin attach() was called with + if (attach(-1) < 0) return; // Attach failed + + write(angle); + safe_delay(servoDelays[this->channel]); + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); +} + +servo_angle_t MarlinServo::read() { + return TERN(OPTIMISTIC_SERVO_READ, this->angle, this->servo.read()); +} + +#endif // HAS_SERVOS +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/Servo.h b/Marlin/src/HAL/HC32/Servo.h new file mode 100644 index 0000000000..0a9715494c --- /dev/null +++ b/Marlin/src/HAL/HC32/Servo.h @@ -0,0 +1,97 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#include + +/** + * return last written value in servo.read instead of calculated value + */ +#define OPTIMISTIC_SERVO_READ + +/** + * @brief servo lib wrapper for marlin + */ +class MarlinServo { +public: + MarlinServo(); + + /** + * @brief attach the pin to the servo, set pin mode, return channel number + * @param pin pin to attach to + * @return channel number, -1 if failed + */ + int8_t attach(const pin_t apin); + + /** + * @brief detach servo + */ + void detach(); + + /** + * @brief is servo attached? + */ + bool attached(); + + /** + * @brief set servo angle + * @param angle new angle + */ + void write(servo_angle_t angle); + + /** + * @brief attach servo, move to angle, delay then detach + * @param angle angle to move to + */ + void move(servo_angle_t angle); + + /** + * @brief read current angle + * @return current angle betwwne 0 and 180 degrees + */ + servo_angle_t read(); + +private: + /** + * @brief internal servo object, provided by arduino core + */ + Servo servo; + + /** + * @brief virtual servo channel + */ + uint8_t channel; + + /** + * @brief pin the servo attached to last + */ + pin_t pin; + + /** + * @brief last known servo angle + */ + servo_angle_t angle; +}; + +// Alias for marlin HAL +typedef MarlinServo hal_servo_t; diff --git a/Marlin/src/HAL/HC32/app_config.h b/Marlin/src/HAL/HC32/app_config.h new file mode 100644 index 0000000000..b971903bba --- /dev/null +++ b/Marlin/src/HAL/HC32/app_config.h @@ -0,0 +1,72 @@ +/** + * app_config.h is included by the hc32f460 arduino build script for every source file. + * it is used to configure the arduino core (and ddl) automatically according + * to the settings in Configuration.h and Configuration_adv.h. + */ +#pragma once +#ifndef _HC32_APP_CONFIG_H_ +#define _HC32_APP_CONFIG_H_ + +#include "../../inc/MarlinConfigPre.h" +#include "sysclock.h" + +// +// dev mode +// +#if ENABLED(MARLIN_DEV_MODE) + #define __DEBUG 1 + #define __CORE_DEBUG 1 +#endif + +// +// Fault Handlers and Panic +// + +#if ENABLED(POSTMORTEM_DEBUGGING) + // disable arduino core fault handler, as we define our own + #define CORE_DISABLE_FAULT_HANDLER 1 +#endif + +// force-enable panic handler so that we can use our custom one (in MinSerial) +#define PANIC_ENABLE 1 + +// use short filenames in ddl debug and core panic output +#define __DEBUG_SHORT_FILENAMES 1 +#define __PANIC_SHORT_FILENAMES 1 + +// omit panic messages in core panic output +#define __OMIT_PANIC_MESSAGE 1 + +// +// Usart +// + +// disable serial globals (Serial1, Serial2, ...), as we define our own +#define DISABLE_SERIAL_GLOBALS 1 + +// increase the size of the Usart buffers (both RX and TX) +// NOTE: +// the heap usage will increase by (SERIAL_BUFFER_SIZE - 64) * "number of serial ports used" +// if running out of heap, the system may become unstable +//#define SERIAL_BUFFER_SIZE 256 + +// enable support for Usart Clock Divider / Oversampling auto config +#define USART_AUTO_CLKDIV_OS_CONFIG 1 + +// enable USART_RX_DMA_SUPPORT core option when SERIAL_DMA is enabled +#if ENABLED(SERIAL_DMA) + #define USART_RX_DMA_SUPPORT 1 +#endif + +// +// Misc. +// + +// redirect printf to host serial +#define REDIRECT_PRINTF_TO_SERIAL 1 + +// F_CPU is F_HCLK, as that's the main CPU core's clock. +// see 'sysclock.h' for more information. +#define F_CPU F_HCLK + +#endif // _HC32_APP_CONFIG_H_ diff --git a/Marlin/src/HAL/HC32/docs/HC32F460 series Datasheet Rev1.3.pdf b/Marlin/src/HAL/HC32/docs/HC32F460 series Datasheet Rev1.3.pdf new file mode 100644 index 0000000000..a8943c819e Binary files /dev/null and b/Marlin/src/HAL/HC32/docs/HC32F460 series Datasheet Rev1.3.pdf differ diff --git a/Marlin/src/HAL/HC32/eeprom/eeprom_bl24cxx.cpp b/Marlin/src/HAL/HC32/eeprom/eeprom_bl24cxx.cpp new file mode 100644 index 0000000000..a53a7c4062 --- /dev/null +++ b/Marlin/src/HAL/HC32/eeprom/eeprom_bl24cxx.cpp @@ -0,0 +1,86 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM." +#endif + +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } + +bool PersistentStore::access_start() { + eeprom_init(); + return true; +} + +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t v = *value; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); + + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + delay(2); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + + crc16(crc, &v, 1); + pos++; + value++; + } + + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing /*=true*/) { + do { + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + + return false; +} + +#endif // IIC_BL24CXX_EEPROM +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/eeprom/eeprom_if_iic.cpp b/Marlin/src/HAL/HC32/eeprom/eeprom_if_iic.cpp new file mode 100644 index 0000000000..0a161f23f2 --- /dev/null +++ b/Marlin/src/HAL/HC32/eeprom/eeprom_if_iic.cpp @@ -0,0 +1,51 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Platform-independent Arduino functions for I2C EEPROM. + * Enable USE_SHARED_EEPROM if not supplied by the framework. + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../../../libs/BL24CXX.h" +#include "../../shared/eeprom_if.h" + +void eeprom_init() { + BL24CXX::init(); +} + +void eeprom_write_byte(uint8_t *pos, unsigned char value) { + const unsigned eeprom_address = (unsigned)pos; + BL24CXX::writeOneByte(eeprom_address, value); +} + +uint8_t eeprom_read_byte(uint8_t *pos) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::readOneByte(eeprom_address); +} + +#endif // IIC_BL24CXX_EEPROM +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/eeprom/eeprom_sdcard.cpp b/Marlin/src/HAL/HC32/eeprom/eeprom_sdcard.cpp new file mode 100644 index 0000000000..759ea5722d --- /dev/null +++ b/Marlin/src/HAL/HC32/eeprom/eeprom_sdcard.cpp @@ -0,0 +1,95 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Implementation of EEPROM settings in SD Card + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(SDCARD_EEPROM_EMULATION) + +#include "../../shared/eeprom_api.h" +#include "../../../sd/cardreader.h" + +#define EEPROM_FILENAME "eeprom.dat" + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } + +#define _ALIGN(x) __attribute__((aligned(x))) +static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE]; + +bool PersistentStore::access_start() { + if (!card.isMounted()) return false; + + MediaFile file, root = card.getroot(); + if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) + return true; // False aborts the save + + int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE); + if (bytes_read < 0) return false; + + for (; bytes_read < long(MARLIN_EEPROM_SIZE); bytes_read++) + HAL_eeprom_data[bytes_read] = 0xFF; + + file.close(); + return true; +} + +bool PersistentStore::access_finish() { + if (!card.isMounted()) return false; + + MediaFile file, root = card.getroot(); + int bytes_written = 0; + if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { + bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE); + file.close(); + } + + return (bytes_written == MARLIN_EEPROM_SIZE); +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + for (size_t i = 0; i < size; i++) HAL_eeprom_data[pos + i] = value[i]; + + crc16(crc, value, size); + pos += size; + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing /*=true*/) { + for (size_t i = 0; i < size; i++) { + const uint8_t c = HAL_eeprom_data[pos + i]; + if (writing) value[i] = c; + crc16(crc, &c, 1); + } + pos += size; + return false; +} + +#endif // SDCARD_EEPROM_EMULATION +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/eeprom/eeprom_wired.cpp b/Marlin/src/HAL/HC32/eeprom/eeprom_wired.cpp new file mode 100644 index 0000000000..997180bd98 --- /dev/null +++ b/Marlin/src/HAL/HC32/eeprom/eeprom_wired.cpp @@ -0,0 +1,95 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + +#warning "SPI / I2C EEPROM has not been tested on HC32F460." + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } + +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::access_start() { + eeprom_init(); + #if ENABLED(SPI_EEPROM) + #if SPI_CHAN_EEPROM1 == 1 + SET_OUTPUT(BOARD_SPI1_SCK_PIN); + SET_OUTPUT(BOARD_SPI1_MOSI_PIN); + SET_INPUT(BOARD_SPI1_MISO_PIN); + SET_OUTPUT(SPI_EEPROM1_CS); + #endif + + spiInit(0); + #endif + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); + uint8_t v = *value; + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing /*=true*/) { + do { + const uint8_t c = eeprom_read_byte((uint8_t *)REAL_EEPROM_ADDR(pos)); + if (writing && value) *value = c; + + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + + return false; +} + +#endif // USE_WIRED_EEPROM +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/endstop_interrupts.cpp b/Marlin/src/HAL/HC32/endstop_interrupts.cpp new file mode 100644 index 0000000000..06c4d0e186 --- /dev/null +++ b/Marlin/src/HAL/HC32/endstop_interrupts.cpp @@ -0,0 +1,118 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "endstop_interrupts.h" +#include "../../module/endstops.h" +#include + +#define ENDSTOP_IRQ_PRIORITY DDL_IRQ_PRIORITY_06 + +// +// IRQ handler +// +void endstopIRQHandler() { + bool flag = false; + + // Check all irq flags + #define CHECK(name) TERN_(USE_##name, flag |= checkIRQFlag(name##_PIN, /*clear*/ true)) + + CHECK(X_MAX); + CHECK(X_MIN); + + CHECK(X2_MAX); + CHECK(X2_MIN); + + CHECK(Y_MAX); + CHECK(Y_MIN); + + CHECK(Y2_MAX); + CHECK(Y2_MIN); + + CHECK(Z_MAX); + CHECK(Z_MIN); + + CHECK(Z2_MAX); + CHECK(Z2_MIN); + + CHECK(Z3_MAX); + CHECK(Z3_MIN); + + CHECK(Z4_MAX); + CHECK(Z4_MIN); + + CHECK(Z_MIN_PROBE); + + // Update endstops + if (flag) endstops.update(); + + #undef CHECK +} + +// +// HAL functions +// +void setup_endstop_interrupts() { + #define SETUP(name) TERN_(USE_##name, attachInterrupt(name##_PIN, endstopIRQHandler, CHANGE); setInterruptPriority(name##_PIN, ENDSTOP_IRQ_PRIORITY)) + + SETUP(X_MAX); + SETUP(X_MIN); + + SETUP(X2_MAX); + SETUP(X2_MIN); + + SETUP(Y_MAX); + SETUP(Y_MIN); + + SETUP(Y2_MAX); + SETUP(Y2_MIN); + + SETUP(Z_MAX); + SETUP(Z_MIN); + + SETUP(Z2_MAX); + SETUP(Z2_MIN); + + SETUP(Z3_MAX); + SETUP(Z3_MIN); + + SETUP(Z4_MAX); + SETUP(Z4_MIN); + + SETUP(Z_MIN_PROBE); + + SETUP(CALIBRATION); + + #undef SETUP +} + +// Ensure 1 - 10 IRQs are registered +// Disable some endstops if you encounter this error +#define ENDSTOPS_INTERRUPTS_COUNT COUNT_ENABLED(USE_X_MAX, USE_X_MIN, USE_X2_MAX, USE_X2_MIN, USE_Y_MAX, USE_Y_MIN, USE_Y2_MAX, USE_Y2_MIN, USE_Z_MAX, USE_Z_MIN, USE_Z2_MAX, USE_Z2_MIN, USE_Z3_MAX, USE_Z3_MIN, USE_Z4_MAX, USE_Z4_MIN, USE_Z_MIN_PROBE, USE_CALIBRATION) +#if ENDSTOPS_INTERRUPTS_COUNT > 10 + #error "Too many endstop interrupts! HC32F460 only supports 10 endstop interrupts." +#elif ENDSTOPS_INTERRUPTS_COUNT == 0 + #error "No endstop interrupts are enabled! Comment out this line to continue." +#endif + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/endstop_interrupts.h b/Marlin/src/HAL/HC32/endstop_interrupts.h new file mode 100644 index 0000000000..124f6f1a1b --- /dev/null +++ b/Marlin/src/HAL/HC32/endstop_interrupts.h @@ -0,0 +1,48 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Endstop interrupts for HC32F460 based targets. + * + * On HC32F460, all pins support external interrupt capability, with some restrictions. + * See the documentation of WInterrupts#attachInterrupt() for details. + * + * TL;DR + * any 16 pins can be used, but only one pin per EXTI line (so PA0 and PB0 are no-good). + */ + +/** + * Endstop Interrupts + * + * Without endstop interrupts the endstop pins must be polled continually in + * the temperature-ISR via endstops.update(), most of the time finding no change. + * With this feature endstops.update() is called only when we know that at + * least one endstop has changed state, saving valuable CPU cycles. + * + * This feature only works when all used endstop pins can generate an 'external interrupt'. + * + * Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'. + * (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino) + */ + +void setup_endstop_interrupts(); diff --git a/Marlin/src/HAL/HC32/fastio.h b/Marlin/src/HAL/HC32/fastio.h new file mode 100644 index 0000000000..af46866172 --- /dev/null +++ b/Marlin/src/HAL/HC32/fastio.h @@ -0,0 +1,69 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Fast I/O interfaces for HC32F460 + * These use GPIO functions instead of Direct Port Manipulation. + */ +#include +#include +#include + +#define READ(IO) (GPIO_GetBit(IO) ? HIGH : LOW) +#define WRITE(IO, V) (((V) > 0) ? GPIO_SetBits(IO) : GPIO_ResetBits(IO)) +#define TOGGLE(IO) (GPIO_Toggle(IO)) + +#define _GET_MODE(IO) getPinMode(IO) +#define _SET_MODE(IO, M) pinMode(IO, M) +#define _SET_OUTPUT(IO) _SET_MODE(IO, OUTPUT) + +#define OUT_WRITE(IO, V) \ + do { \ + _SET_OUTPUT(IO); \ + WRITE(IO, V); \ + } while (0) + +#define SET_INPUT(IO) _SET_MODE(IO, INPUT_FLOATING) +#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) +#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) +#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) +#define SET_PWM(IO) _SET_MODE(IO, OUTPUT_PWM) + +#define IS_INPUT(IO) ( \ + _GET_MODE(IO) == INPUT || \ + _GET_MODE(IO) == INPUT_FLOATING || \ + _GET_MODE(IO) == INPUT_ANALOG || \ + _GET_MODE(IO) == INPUT_PULLUP || \ + _GET_MODE(IO) == INPUT_PULLDOWN) + +#define IS_OUTPUT(IO) ( \ + _GET_MODE(IO) == OUTPUT || \ + _GET_MODE(IO) == OUTPUT_PWM || \ + _GET_MODE(IO) == OUTPUT_OPEN_DRAIN) + +#define PWM_PIN(IO) isAnalogWritePin(IO) + +#define extDigitalRead(IO) digitalRead(IO) +#define extDigitalWrite(IO, V) digitalWrite(IO, V) + +#define NO_COMPILE_TIME_PWM // Can't check for PWM at compile time diff --git a/Marlin/src/HAL/HC32/inc/Conditionals_LCD.h b/Marlin/src/HAL/HC32/inc/Conditionals_LCD.h new file mode 100644 index 0000000000..8266da4b2a --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/Conditionals_LCD.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) + #define U8G_SW_SPI_HC32 1 +#endif diff --git a/Marlin/src/HAL/HC32/inc/Conditionals_adv.h b/Marlin/src/HAL/HC32/inc/Conditionals_adv.h new file mode 100644 index 0000000000..06f15e5105 --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/Conditionals_adv.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifndef TEMP_SOC_PIN + #define TEMP_SOC_PIN 0xFF // Dummy that is not a valid GPIO, HAL checks for this +#endif diff --git a/Marlin/src/HAL/HC32/inc/Conditionals_post.h b/Marlin/src/HAL/HC32/inc/Conditionals_post.h new file mode 100644 index 0000000000..bcffd5a8d5 --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/Conditionals_post.h @@ -0,0 +1,34 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation +#if USE_FALLBACK_EEPROM + #define SDCARD_EEPROM_EMULATION +#elif ANY(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 +#endif + +// Allow SD support to be disabled +#if !HAS_MEDIA + #undef ONBOARD_SDIO +#endif diff --git a/Marlin/src/HAL/HC32/inc/Conditionals_type.h b/Marlin/src/HAL/HC32/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/HC32/inc/SanityCheck.h b/Marlin/src/HAL/HC32/inc/SanityCheck.h new file mode 100644 index 0000000000..c6b3b221df --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/SanityCheck.h @@ -0,0 +1,107 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once +#include + +#if !defined(ARDUINO_CORE_VERSION_INT) || !defined(GET_VERSION_INT) + // version macros were introduced in arduino core version 1.1.0 + // below that version, we polyfill them + #define GET_VERSION_INT(major, minor, patch) ((major * 100000) + (minor * 1000) + patch) + #define ARDUINO_CORE_VERSION_INT GET_VERSION_INT(1, 0, 0) +#endif + +#if ARDUINO_CORE_VERSION_INT < GET_VERSION_INT(1, 1, 0) + // because we use app_config.h introduced in arduino core version 1.1.0, the + // HAL is not compatible with older versions + #error "The HC32 HAL is not compatible with Arduino Core versions < 1.1.0. Consider updating the Arduino Core." +#endif + +#ifndef BOARD_XTAL_FREQUENCY + #error "BOARD_XTAL_FREQUENCY is required for HC32F460." +#endif + +#if ENABLED(FAST_PWM_FAN) + #error "FAST_PWM_FAN is not yet implemented for this platform." +#endif + +#if !defined(HAVE_SW_SERIAL) && HAS_TMC_SW_SERIAL + #error "Missing SoftwareSerial implementation." +#endif + +#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA + #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise + #if USE_FALLBACK_EEPROM + #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." + #endif + + #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." +#endif + +#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." +#elif ENABLED(SERIAL_STATS_DROPPED_RX) + #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." +#endif + +#if ENABLED(NEOPIXEL_LED) && DISABLED(MKS_MINI_12864_V3) + #error "NEOPIXEL_LED (Adafruit NeoPixel) is not supported for HC32F460. Comment out this line to proceed at your own risk!" +#endif + +// Emergency Parser needs at least one serial with HardwareSerial. +#if ENABLED(EMERGENCY_PARSER) && ((SERIAL_PORT == -1 && !defined(SERIAL_PORT_2)) || (SERIAL_PORT_2 == -1 && !defined(SERIAL_PORT))) + #error "EMERGENCY_PARSER is only supported by HardwareSerial on HC32F460." +#endif + +#if TEMP_SENSOR_SOC + #ifndef TEMP_SOC_PIN + #error "TEMP_SOC_PIN must be defined to use TEMP_SENSOR_SOC." + #elif IS_GPIO_PIN(TEMP_SOC_PIN) + #error "TEMP_SOC_PIN must not be a valid GPIO pin to avoid conflicts." + #endif +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) && !defined(CORE_DISABLE_FAULT_HANDLER) + #error "POSTMORTEM_DEBUGGING requires CORE_DISABLE_FAULT_HANDLER to be set." +#endif + +#ifdef PANIC_ENABLE + #if defined(PANIC_USART1_TX_PIN) || defined(PANIC_USART2_TX_PIN) || defined(PANIC_USART3_TX_PIN) || defined(PANIC_USART3_TX_PIN) + #error "HC32 HAL uses a custom panic handler. Do not define PANIC_USARTx_TX_PIN." + #endif +#endif + +#if ENABLED(SERIAL_DMA) + #if !defined(USART_RX_DMA_SUPPORT) + #error "SERIAL_DMA requires USART_RX_DMA_SUPPORT to be enabled in the arduino core." + #endif + + // Before arduino core version 1.2.0, USART_RX_DMA_SUPPORT did not implement + // core_hook_usart_rx_irq, which is required for the emergency parser. + // With 1.2.0, this was fixed (see https://github.com/shadow578/framework-arduino-hc32f46x/pull/25). + #if ENABLED(EMERGENCY_PARSER) && ARDUINO_CORE_VERSION_INT < GET_VERSION_INT(1, 2, 0) + #error "EMERGENCY_PARSER is not supported with SERIAL_DMA. Please disable either SERIAL_DMA or EMERGENCY_PARSER." + #endif + + #if ARDUINO_CORE_VERSION_INT < GET_VERSION_INT(1, 1, 0) + #error "SERIAL_DMA is not supported with arduino core version < 1.1.0." + #endif +#endif diff --git a/Marlin/src/HAL/HC32/pinsDebug.h b/Marlin/src/HAL/HC32/pinsDebug.h new file mode 100644 index 0000000000..9f8e23ce44 --- /dev/null +++ b/Marlin/src/HAL/HC32/pinsDebug.h @@ -0,0 +1,183 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Pins Debugging for HC32 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + +#include "../../inc/MarlinConfig.h" +#include "fastio.h" +#include + +#ifndef BOARD_NR_GPIO_PINS + #error "Expected BOARD_NR_GPIO_PINS not found." +#endif + +#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS +#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS +#define isValidPin(P) IS_GPIO_PIN(P) + +// Note: pin_array is defined in `Marlin/src/pins/pinsDebug.h`, and since this file is included +// after it, it is available in this file as well. +#define getPinByIndex(x) pin_t(pin_array[x].pin) +#define digitalRead_mod(P) extDigitalRead(P) + +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(P)); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) + +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) + +#define MULTI_NAME_PAD 21 // Space needed to be pretty if not first name assigned to a pin + +// +// Pins that will cause a hang / reset / disconnect in M43 Toggle and Watch utils +// +#ifndef M43_NEVER_TOUCH + // Don't touch any of the following pins: + // - Host serial pins, and + // - Pins that could be connected to oscillators (see datasheet, Table 2.1): + // - XTAL = PH0, PH1 + // - XTAL32 = PC14, PC15 + #define IS_HOST_USART_PIN(Q) (Q == BOARD_USART2_TX_PIN || Q == BOARD_USART2_RX_PIN) + #define IS_OSC_PIN(Q) (Q == PH0 || Q == PH1 || Q == PC14 || Q == PC15) + + #define M43_NEVER_TOUCH(Q) (IS_HOST_USART_PIN(Q) || IS_OSC_PIN(Q)) +#endif + +int8_t digitalPinToAnalogIndex(const pin_t pin) { + if (!isValidPin(pin)) return -1; + const int8_t adc_channel = int8_t(PIN_MAP[pin].adc_info.channel); + return pin_t(adc_channel); +} + +bool isAnalogPin(pin_t pin) { + if (!isValidPin(pin)) return false; + + if (PIN_MAP[pin].adc_info.channel != ADC_PIN_INVALID) + return _GET_MODE(pin) == INPUT_ANALOG && !M43_NEVER_TOUCH(pin); + + return false; +} + +bool getValidPinMode(const pin_t pin) { + return isValidPin(pin) && !IS_INPUT(pin); +} + +bool getPinIsDigitalByIndex(const int16_t index) { + const pin_t pin = getPinByIndex(index); + return (!isAnalogPin(pin)); +} + +/** + * @brief print pin PWM status + * @return true if pin is currently a PWM pin, false otherwise + */ +bool pwm_status(const pin_t pin) { + // Get timer assignment for pin + timera_config_t *unit; + en_timera_channel_t channel; + en_port_func_t port_function; + if (!timera_get_assignment(pin, unit, channel, port_function) || unit == nullptr) { + // No pwm pin or no unit assigned + return false; + } + + // A pin that is PWM output is: + // - Assigned to a timerA unit (tested above) + // - Unit is initialized + // - Channel is active + // - PinMode is OUTPUT_PWM + return timera_is_unit_initialized(unit) && timera_is_channel_active(unit, channel) && getPinMode(pin) == OUTPUT_PWM; +} + +void printPinPWM(const pin_t pin) { + // Get timer assignment for pin + timera_config_t *unit; + en_timera_channel_t channel; + en_port_func_t port_function; + if (!timera_get_assignment(pin, unit, channel, port_function) || unit == nullptr) + return; // No pwm pin or no unit assigned + + // Print timer assignment of pin, eg. "TimerA1Ch2 Func4" + SERIAL_ECHOPGM("TimerA", TIMERA_REG_TO_X(unit->peripheral.register_base), + "Ch", TIMERA_CHANNEL_TO_X(channel), + " Func", int(port_function)); + SERIAL_ECHO_SP(3); // 3 spaces + + // Print timer unit state, eg. "1/16 PERAR=1234" OR "N/A" + if (timera_is_unit_initialized(unit)) { + // Unit initialized, print + // - Timer clock divider + // - Timer period value (PERAR) + const uint8_t clock_divider = timera_clk_div_to_n(unit->state.base_init->enClkDiv); + const uint16_t period = TIMERA_GetPeriodValue(unit->peripheral.register_base); + SERIAL_ECHOPGM("1/", clock_divider, " PERAR=", period); + } + else { + // Unit not initialized + SERIAL_ECHOPGM("N/A"); + return; + } + + SERIAL_ECHO_SP(3); // 3 spaces + + // Print timer channel state, e.g. "CMPAR=1234" OR "N/A" + if (timera_is_channel_active(unit, channel)) { + // Channel active, print + // - Channel compare value + const uint16_t compare = TIMERA_GetCompareValue(unit->peripheral.register_base, channel); + SERIAL_ECHOPGM("CMPAR=", compare); + } + else { + // Channel inactive + SERIAL_ECHOPGM("N/A"); + } +} + +void printPinPort(pin_t pin) { + const char port = 'A' + char(pin >> 4); // Pin div 16 + const int16_t gbit = PIN_MAP[pin].bit_pos; + char buffer[8]; + sprintf_P(buffer, PSTR("P%c%hd "), port, gbit); + if (gbit < 10) { + SERIAL_CHAR(' '); + } + + SERIAL_ECHO(buffer); +} diff --git a/Marlin/src/HAL/HC32/printf_retarget.cpp b/Marlin/src/HAL/HC32/printf_retarget.cpp new file mode 100644 index 0000000000..8a48aca3d4 --- /dev/null +++ b/Marlin/src/HAL/HC32/printf_retarget.cpp @@ -0,0 +1,55 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef ARDUINO_ARCH_HC32 +#ifdef REDIRECT_PRINTF_TO_SERIAL + +#ifndef __GNUC__ + #error "only GCC is supported" +#endif + +#include "../../inc/MarlinConfig.h" + +/** + * @brief implementation of _write that redirects everything to the host serial(s) + * @param file file descriptor. don't care + * @param ptr pointer to the data to write + * @param len length of the data to write + * @return number of bytes written + */ +extern "C" int _write(int file, char *ptr, int len) { + //SERIAL_ECHO_START(); // echo: + for (int i = 0; i < len; i++) SERIAL_CHAR(ptr[i]); + return len; +} + +/** + * @brief implementation of _isatty that always returns 1 + * @param file file descriptor. don't care + * @return everything is a tty. there are no files to be had + */ +extern "C" int _isatty(int file) { + return 1; +} + +#endif // REDIRECT_PRINTF_TO_SERIAL +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/sdio.cpp b/Marlin/src/HAL/HC32/sdio.cpp new file mode 100644 index 0000000000..3c4038f92d --- /dev/null +++ b/Marlin/src/HAL/HC32/sdio.cpp @@ -0,0 +1,146 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "sdio.h" +#include +#include + +// +// SDIO configuration +// + +#define SDIO_PERIPHERAL M4_SDIOC1 + +// Use DMA2 channel 0 +#define SDIO_DMA_PERIPHERAL M4_DMA2 +#define SDIO_DMA_CHANNEL DmaCh0 + +// SDIO read/write operation retries and timeouts +#define SDIO_READ_RETRIES 3 +#define SDIO_READ_TIMEOUT 100 // ms + +#define SDIO_WRITE_RETRIES 1 +#define SDIO_WRITE_TIMEOUT 100 // ms + +// +// HAL functions +// + +#define WITH_RETRY(retries, fn) \ + for (int retry = 0; retry < (retries); retry++) { \ + MarlinHAL::watchdog_refresh(); \ + yield(); \ + fn \ + } + +stc_sd_handle_t *handle = nullptr; + +bool SDIO_Init() { + // Configure SDIO pins + GPIO_SetFunc(BOARD_SDIO_D0, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D1, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D2, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D3, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_CLK, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_CMD, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_DET, Func_Sdio); + + // If a handle is already initialized, free it before creating a new one + // otherwise, we will leak memory, which will eventually crash the system + if (handle != nullptr) { + delete handle->pstcDmaInitCfg; + delete handle->pstcCardInitCfg; + delete handle; + handle = nullptr; + } + + // Create DMA configuration + stc_sdcard_dma_init_t *dmaConf = new stc_sdcard_dma_init_t; + dmaConf->DMAx = SDIO_DMA_PERIPHERAL; + dmaConf->enDmaCh = SDIO_DMA_CHANNEL; + + // Create card configuration + // This should be a fairly safe configuration for most cards + stc_sdcard_init_t *cardConf = new stc_sdcard_init_t; + cardConf->enBusWidth = SdiocBusWidth4Bit; + cardConf->enClkFreq = SdiocClk400K; + cardConf->enSpeedMode = SdiocNormalSpeedMode; + cardConf->pstcInitCfg = nullptr; + + // Create handle in DMA mode + handle = new stc_sd_handle_t; + handle->SDIOCx = SDIO_PERIPHERAL; + handle->enDevMode = SdCardDmaMode; + handle->pstcDmaInitCfg = dmaConf; + //handle->pstcCardInitCfg = cardConf; // assigned in SDCARD_Init + + // Initialize sd card + en_result_t rc = SDCARD_Init(handle, cardConf); + if (rc != Ok) printf("SDIO_Init() error (rc=%u)\n", rc); + + return rc == Ok; +} + +bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { + CORE_ASSERT(handle != nullptr, "SDIO not initialized", return false); + CORE_ASSERT(dst != nullptr, "SDIO_ReadBlock dst is NULL", return false); + + WITH_RETRY(SDIO_READ_RETRIES, { + en_result_t rc = SDCARD_ReadBlocks(handle, block, 1, dst, SDIO_READ_TIMEOUT); + if (rc == Ok) return true; + printf("SDIO_ReadBlock error (rc=%u; ErrorCode=%lu)\n", rc, handle->u32ErrorCode); + }) + + return false; +} + +bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { + CORE_ASSERT(handle != nullptr, "SDIO not initialized", return false); + CORE_ASSERT(src != nullptr, "SDIO_WriteBlock src is NULL", return false); + + WITH_RETRY(SDIO_WRITE_RETRIES, { + en_result_t rc = SDCARD_WriteBlocks(handle, block, 1, (uint8_t *)src, SDIO_WRITE_TIMEOUT); + if (rc == Ok) return true; + printf("SDIO_WriteBlock error (rc=%u; ErrorCode=%lu)\n", rc, handle->u32ErrorCode); + }) + + return false; +} + +bool SDIO_IsReady() { + CORE_ASSERT(handle != nullptr, "SDIO not initialized", return false); + return bool(handle->stcCardStatus.READY_FOR_DATA); +} + +uint32_t SDIO_GetCardSize() { + CORE_ASSERT(handle != nullptr, "SDIO not initialized", return 0); + + // Multiply number of blocks with block size to get size in bytes + const uint64_t cardSizeBytes = uint64_t(handle->stcSdCardInfo.u32LogBlockNbr) * uint64_t(handle->stcSdCardInfo.u32LogBlockSize); + + // If the card is bigger than ~4Gb (maximum a 32bit integer can hold), clamp to the maximum value of a 32 bit integer + return _MAX(cardSizeBytes, UINT32_MAX); +} + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/sdio.h b/Marlin/src/HAL/HC32/sdio.h new file mode 100644 index 0000000000..89d4b061b1 --- /dev/null +++ b/Marlin/src/HAL/HC32/sdio.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2017 Victor Perez + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once +#include "../../inc/MarlinConfig.h" + +bool SDIO_Init(); +bool SDIO_ReadBlock(uint32_t block, uint8_t *dst); +bool SDIO_WriteBlock(uint32_t block, const uint8_t *src); +bool SDIO_IsReady(); +uint32_t SDIO_GetCardSize(); diff --git a/Marlin/src/HAL/HC32/spi_pins.h b/Marlin/src/HAL/HC32/spi_pins.h new file mode 100644 index 0000000000..5f1a94e920 --- /dev/null +++ b/Marlin/src/HAL/HC32/spi_pins.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once diff --git a/Marlin/src/HAL/HC32/sysclock.cpp b/Marlin/src/HAL/HC32/sysclock.cpp new file mode 100644 index 0000000000..e98395c42e --- /dev/null +++ b/Marlin/src/HAL/HC32/sysclock.cpp @@ -0,0 +1,242 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * HC32f460 system clock configuration + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" +#include "sysclock.h" + +#include +#include + +/*** + * @brief Automatically calculate M, N, P values for the MPLL to reach a target frequency. + * @param input_frequency The input frequency. + * @param target_frequency The target frequency. + * @return The MPLL configuration structure. Q and R are not set. + * + * @note + * Simplified MPLL block diagram, with intermediary clocks (1) = VCO_in, (2) = VCO_out: + * + * INPUT -> [/ M] -(1)-> [* N] -(2)-|-> [/ P] -> MPLL-P + */ +constexpr stc_clk_mpll_cfg_t get_mpll_config(double input_frequency, double target_frequency) { + // PLL input clock divider: M in [1, 24] + for (uint32_t M = 1; M <= 24; M++) { + double f_vco_in = input_frequency / M; + + // 1 <= VCO_in <= 25 MHz + if (f_vco_in < 1e6 || f_vco_in > 25e6) continue; + + // VCO multiplier: N in [20, 480] + for (uint32_t N = 20; N <= 480; N++) { + double f_vco_out = f_vco_in * N; + + // 240 <= VCO_out <= 480 MHz + if (f_vco_out < 240e6 || f_vco_out > 480e6) continue; + + // Output "P" divider: P in [2, 16] + for (uint32_t P = 2; P <= 16; P++) { + double f_calculated_out = f_vco_out / P; + if (f_calculated_out == target_frequency) { + // Found a match, return it + return { + .PllpDiv = P, + .PllqDiv = P, // Don't care for Q and R + .PllrDiv = P, // " + .plln = N, + .pllmDiv = M + }; + } + } + } + } + + // If no valid M, N, P found, return invalid config + return { 0, 0, 0, 0, 0 }; +} + +/** + * @brief Get the division factor required to get the target frequency from the input frequency. + * @tparam input_freq The input frequency. + * @tparam target_freq The target frequency. + * @return The division factor. + */ +template +constexpr en_clk_sysclk_div_factor_t get_division_factor() { + // Calculate the divider to get the target frequency + constexpr float fdivider = static_cast(input_freq) / static_cast(target_freq); + constexpr int divider = static_cast(fdivider); + + // divider must be an integer + static_assert(fdivider == divider, "Target frequency not achievable, divider must be an integer"); + + // divider must be between 1 and 64 (enum range), and must be a power of 2 + static_assert(divider >= 1 && divider <= 64, "Invalid divider, out of range"); + static_assert((divider & (divider - 1)) == 0, "Invalid divider, not a power of 2"); + + // return the divider + switch (divider) { + case 1: return ClkSysclkDiv1; + case 2: return ClkSysclkDiv2; + case 4: return ClkSysclkDiv4; + case 8: return ClkSysclkDiv8; + case 16: return ClkSysclkDiv16; + case 32: return ClkSysclkDiv32; + case 64: return ClkSysclkDiv64; + } +} + +/** + * @brief Validate the runtime clocks match the expected values. + */ +void validate_system_clocks() { + #define CLOCK_ASSERT(expected, actual) \ + if (expected != actual) { \ + SERIAL_ECHOPGM( \ + "Clock Mismatch for " #expected ": " \ + "expected ", expected, \ + ", got ", actual \ + ); \ + CORE_ASSERT_FAIL("Clock Mismatch: " #expected); \ + } + + update_system_clock_frequencies(); + + CLOCK_ASSERT(F_SYSTEM_CLOCK, SYSTEM_CLOCK_FREQUENCIES.system); + CLOCK_ASSERT(F_HCLK, SYSTEM_CLOCK_FREQUENCIES.hclk); + CLOCK_ASSERT(F_EXCLK, SYSTEM_CLOCK_FREQUENCIES.exclk); + CLOCK_ASSERT(F_PCLK0, SYSTEM_CLOCK_FREQUENCIES.pclk0); + CLOCK_ASSERT(F_PCLK1, SYSTEM_CLOCK_FREQUENCIES.pclk1); + CLOCK_ASSERT(F_PCLK2, SYSTEM_CLOCK_FREQUENCIES.pclk2); + CLOCK_ASSERT(F_PCLK3, SYSTEM_CLOCK_FREQUENCIES.pclk3); + CLOCK_ASSERT(F_PCLK4, SYSTEM_CLOCK_FREQUENCIES.pclk4); +} + +/** + * @brief Configure HC32 system clocks. + * + * This function is called by the Arduino core early in the startup process, before setup() is called. + * It is used to configure the system clocks to the desired state. + * + * See https://github.com/MarlinFirmware/Marlin/pull/27099 for more information. + */ +void core_hook_sysclock_init() { + // Set wait cycles, as we are about to switch to 200 MHz HCLK + sysclock_configure_flash_wait_cycles(); + sysclock_configure_sram_wait_cycles(); + + // Select MPLL input frequency based on clock availability + #if BOARD_XTAL_FREQUENCY == 8000000 || BOARD_XTAL_FREQUENCY == 16000000 // 8 MHz or 16 MHz XTAL + constexpr uint32_t mpll_input_clock = BOARD_XTAL_FREQUENCY; + + sysclock_configure_xtal(); + + #if BOARD_XTAL_FREQUENCY == 16000000 + #warning "HC32F460 with 16 MHz XTAL has not been tested." + #endif + + #else // HRC (16 MHz) + + constexpr uint32_t mpll_input_clock = 16000000; + + sysclock_configure_hrc(); + + // HRC could have been configured by ICG to 20 MHz + // TODO: handle gracefully if HRC is not 16 MHz + if (1UL != (HRC_FREQ_MON() & 1UL)) { + panic("HRC is not 16 MHz"); + } + + #ifdef BOARD_XTAL_FREQUENCY + #warning "No valid XTAL frequency defined, falling back to HRC." + #endif + + #endif + + // Automagically calculate MPLL configuration + constexpr stc_clk_mpll_cfg_t pllConf = get_mpll_config(mpll_input_clock, F_SYSTEM_CLOCK); + static_assert(pllConf.pllmDiv != 0 && pllConf.plln != 0 && pllConf.PllpDiv != 0, "MPLL auto-configuration failed"); + sysclock_configure_mpll(ClkPllSrcXTAL, &pllConf); + + // Setup clock divisors + constexpr stc_clk_sysclk_cfg_t sysClkConf = { + .enHclkDiv = get_division_factor(), + .enExclkDiv = get_division_factor(), + .enPclk0Div = get_division_factor(), + .enPclk1Div = get_division_factor(), + .enPclk2Div = get_division_factor(), + .enPclk3Div = get_division_factor(), + .enPclk4Div = get_division_factor(), + }; + sysclock_set_clock_dividers(&sysClkConf); + + // Set power mode, before switch + power_mode_update_pre(F_SYSTEM_CLOCK); + + // Switch to MPLL-P as system clock source + CLK_SetSysClkSource(CLKSysSrcMPLL); + + // Set power mode, after switch + power_mode_update_post(F_SYSTEM_CLOCK); + + // Verify clocks match expected values (at runtime) + #if ENABLED(MARLIN_DEV_MODE) || ENABLED(ALWAYS_VALIDATE_CLOCKS) + validate_system_clocks(); + #endif + + // Verify clock configuration (at compile time) + #if ARDUINO_CORE_VERSION_INT >= GET_VERSION_INT(1, 2, 0) + assert_mpll_config_valid< + mpll_input_clock, + pllConf.pllmDiv, + pllConf.plln, + pllConf.PllpDiv, + pllConf.PllqDiv, + pllConf.PllrDiv + >(); + + assert_system_clocks_valid< + F_SYSTEM_CLOCK, + sysClkConf.enHclkDiv, + sysClkConf.enPclk0Div, + sysClkConf.enPclk1Div, + sysClkConf.enPclk2Div, + sysClkConf.enPclk3Div, + sysClkConf.enPclk4Div, + sysClkConf.enExclkDiv + >(); + + static_assert(get_mpll_output_clock( + mpll_input_clock, + pllConf.pllmDiv, + pllConf.plln, + pllConf.PllpDiv + ) == F_SYSTEM_CLOCK, "actual MPLL output clock does not match F_SYSTEM_CLOCK"); + #endif +} + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/sysclock.h b/Marlin/src/HAL/HC32/sysclock.h new file mode 100644 index 0000000000..783d5677e9 --- /dev/null +++ b/Marlin/src/HAL/HC32/sysclock.h @@ -0,0 +1,65 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * HC32F460 system clock configuration. + * + * With the HC32 HAL, the various peripheral clocks (including the CPU clock) are derived + * from the main PLL (MPLL-P) output (referred to at F_SYSTEM_CLOCK). + * + * F_SYSTEM_CLOCK is the target frequency of the main PLL, and the PLL is automatically configured + * to achieve this frequency. + * + * The peripheral clocks are the result of integer division of F_SYSTEM_CLOCK. + * Their target frequencies are defined here, and the required division factors are calculated automatically. + * Note that the division factor must be a power of 2 between 1 and 64. + * If the target frequency is not achievable, a compile-time error will be generated. + * + * Additionally, there are interdependencies between the peripheral clocks, which are described in + * Section 4.4 "Working Clock Specifications" of the HC32F460 Reference Manual. + * With Arduino core >= 1.2.0, these interdependencies are checked at compile time. + * On earlier versions, you are on your own. + * + * For all clock frequencies, they can be checked at runtime by enabling the 'ALWAYS_VALIDATE_CLOCKS' define. + * In MARLIN_DEV_MODE, they will also be printed to the serial console by 'MarlinHAL::HAL_clock_frequencies_dump'. + * + * See https://github.com/MarlinFirmware/Marlin/pull/27099 for more information. + */ + +// Target peripheral clock frequencies, must be integer divisors of F_SYSTEM_CLOCK. +// Changing the frequency here will automagically update everything else. +#define F_HCLK 200000000UL // 200 MHz; CPU +#define F_EXCLK (F_HCLK / 2) // 100 MHz; SDIO +#define F_PCLK0 (F_HCLK / 2) // 100 MHz; Timer6 (unused) +#define F_PCLK1 (F_HCLK / 4) // 50 MHz; USART, SPI, Timer0 (step + temp), TimerA (Servo) +#define F_PCLK2 (F_HCLK / 8) // 25 MHz; ADC Sampling +#define F_PCLK3 (F_HCLK / 8) // 25 MHz; I2C, WDT +#define F_PCLK4 (F_HCLK / 2) // 100 MHz; ADC Control + +// MPLL-P clock target frequency. This must be >= the highest peripheral clock frequency. +// PLL config is automatically calculated based on this value. +#define F_SYSTEM_CLOCK F_HCLK + +// The Peripheral clocks are only checked at runtime if this is enabled OR MARLIN_DEV_MODE is enabled. +// Compile time checks are always performed with Arduino core version >= 1.2.0. +#define ALWAYS_VALIDATE_CLOCKS 1 diff --git a/Marlin/src/HAL/HC32/timers.cpp b/Marlin/src/HAL/HC32/timers.cpp new file mode 100644 index 0000000000..b8eab34cf7 --- /dev/null +++ b/Marlin/src/HAL/HC32/timers.cpp @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "timers.h" +#include + +/** + * Timer0 Unit 2 Channel A is used for Temperature interrupts + */ +Timer0 temp_timer(&TIMER02A_config, &Temp_Handler); + +/** + * Timer0 Unit 2 Channel B is used for Step interrupts + */ +Timer0 step_timer(&TIMER02B_config, &Step_Handler); + +void HAL_timer_start(const timer_channel_t timer_ch, const uint32_t frequency) { + if (timer_ch == MF_TIMER_TEMP) { + CORE_DEBUG_PRINTF("HAL_timer_start: temp timer, f=%ld\n", long(frequency)); + timer_ch->start(frequency, TEMP_TIMER_PRESCALE); + timer_ch->setCallbackPriority(TEMP_TIMER_PRIORITY); + } + else if (timer_ch == MF_TIMER_STEP) { + CORE_DEBUG_PRINTF("HAL_timer_start: step timer, f=%ld\n", long(frequency)); + timer_ch->start(frequency, STEPPER_TIMER_PRESCALE); + timer_ch->setCallbackPriority(STEP_TIMER_PRIORITY); + } + else { + CORE_ASSERT_FAIL("HAL_timer_start: invalid timer_ch") + } +} + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/timers.h b/Marlin/src/HAL/HC32/timers.h new file mode 100644 index 0000000000..8a4465e2d8 --- /dev/null +++ b/Marlin/src/HAL/HC32/timers.h @@ -0,0 +1,131 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2017 Victor Perez + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ +#pragma once +#include +#include +#include "sysclock.h" + +// +// Timer Types +// +typedef Timer0 *timer_channel_t; +typedef uint16_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) + +// +// Timer instances +// +extern Timer0 temp_timer; +extern Timer0 step_timer; + +// +// Timer Configurations +// + +/** + * HAL_TIMER_RATE must be known at compile time since it's used to calculate + * STEPPER_TIMER_RATE, which is used in 'constexpr' calculations. + * On the HC32F460 the timer rate depends on PCLK1, which is derived from the + * system clock configured at runtime. + * Thus we use the 'F_PCLK1' constant defined in 'sysclock.h'. + * + * See https://github.com/MarlinFirmware/Marlin/pull/27099 for more information. + * + * NOTE: If the 'constexpr' requirement is ever lifted, TIMER0_BASE_FREQUENCY could + * be used instead. Tho this would probably not make any noticeable difference. + */ +#define HAL_TIMER_RATE F_PCLK1 + +// Temperature timer +#define MF_TIMER_TEMP (&temp_timer) +#define TEMP_TIMER_PRIORITY DDL_IRQ_PRIORITY_02 +#define TEMP_TIMER_PRESCALE 16UL // 12.5MHz +#define TEMP_TIMER_RATE 1000 // 1kHz +#define TEMP_TIMER_FREQUENCY TEMP_TIMER_RATE // 1kHz also + +// Stepper timer +#define MF_TIMER_STEP (&step_timer) +#define STEP_TIMER_PRIORITY DDL_IRQ_PRIORITY_00 // Top priority, nothing else uses it +#define STEPPER_TIMER_PRESCALE 16UL // 12.5MHz + +#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // 50MHz / 16 = 3.125MHz +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // Integer 3 + +// Pulse timer (== stepper timer) +#define MF_TIMER_PULSE MF_TIMER_STEP +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE + +// +// HAL functions +// +void HAL_timer_start(const timer_channel_t timer_ch, const uint32_t frequency); + +// Inlined since they are somewhat critical +#define MARLIN_HAL_TIMER_INLINE_ATTR __attribute__((always_inline)) inline + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_enable_interrupt(const timer_channel_t timer_ch) { + timer_ch->resume(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_disable_interrupt(const timer_channel_t timer_ch) { + timer_ch->pause(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR bool HAL_timer_interrupt_enabled(const timer_channel_t timer_ch) { + return timer_ch->isPaused(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_set_compare(const timer_channel_t timer_ch, const hal_timer_t compare) { + timer_ch->setCompareValue(compare); +} + +MARLIN_HAL_TIMER_INLINE_ATTR hal_timer_t HAL_timer_get_count(const timer_channel_t timer_ch) { + return timer_ch->getCount(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_isr_prologue(const timer_channel_t timer_ch) { + timer_ch->clearInterruptFlag(); +} + +inline void HAL_timer_isr_epilogue(const timer_channel_t) {} + +// +// HAL function aliases +// +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) + +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP); + +// +// HAL ISR callbacks +// +void Step_Handler(); +void Temp_Handler(); + +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() void Step_Handler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() void Temp_Handler() +#endif diff --git a/Marlin/src/HAL/HC32/u8g/LCD_defines.h b/Marlin/src/HAL/HC32/u8g/LCD_defines.h new file mode 100644 index 0000000000..cb5a6812ef --- /dev/null +++ b/Marlin/src/HAL/HC32/u8g/LCD_defines.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * HC32 LCD-specific defines + */ + +uint8_t u8g_com_HAL_HC32_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); +#define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_HC32_sw_spi_fn diff --git a/Marlin/src/HAL/HC32/u8g/u8g_com_HAL_HC32_sw_spi.cpp b/Marlin/src/HAL/HC32/u8g/u8g_com_HAL_HC32_sw_spi.cpp new file mode 100644 index 0000000000..97f4b85eaf --- /dev/null +++ b/Marlin/src/HAL/HC32/u8g/u8g_com_HAL_HC32_sw_spi.cpp @@ -0,0 +1,163 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "../../../inc/MarlinConfig.h" + +#if U8G_SW_SPI_HC32 + +#warning "Software SPI for U8Glib is experimental on HC32F460. Please share your experiences at https://github.com/shadow578/Marlin-H32/issues/35" + +#include +#include "../../shared/HAL_SPI.h" + +#ifndef LCD_SPI_SPEED + #define LCD_SPI_SPEED SPI_FULL_SPEED // Fastest + //#define LCD_SPI_SPEED SPI_QUARTER_SPEED // Slower +#endif + +static uint8_t SPI_speed = LCD_SPI_SPEED; + +static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { + for (i = 0; i < 8; ++i) { + if (spi_speed == 0) { + WRITE(DOGLCD_MOSI, !!(b & 0x80)); + WRITE(DOGLCD_SCK, HIGH); + b <<= 1; + if (miso_pin >= 0 && READ(miso_pin)) b |= 1; + WRITE(DOGLCD_SCK, LOW); + } + else { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + for (j = 0; j < spi_speed; ++j) WRITE(DOGLCD_MOSI, state); + for (j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1; ++j)) WRITE(DOGLCD_SCK, HIGH); + + b <<= 1; + if (miso_pin >= 0 && READ(miso_pin)) b |= 1; + + for (j = 0; j < spi_speed; ++j) WRITE(DOGLCD_SCK, LOW); + } + } + return b; +} + +static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { + for (i = 0; i < 8; ++i) { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + if (spi_speed == 0) { + WRITE(DOGLCD_SCK, LOW); + WRITE(DOGLCD_MOSI, state); + WRITE(DOGLCD_MOSI, state); // need some setup time + WRITE(DOGLCD_SCK, HIGH); + } + else { + for (j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE(DOGLCD_SCK, LOW); + for (j = 0; j < spi_speed; ++j) WRITE(DOGLCD_MOSI, state); + for (j = 0; j < spi_speed; ++j) WRITE(DOGLCD_SCK, HIGH); + } + b <<= 1; + if (miso_pin >= 0 && READ(miso_pin)) b |= 1; + } + return b; +} + +static void u8g_sw_spi_shift_out(uint8_t val) { + #if U8G_SPI_USE_MODE_3 + swSpiTransfer_mode_3(val, SPI_speed); + #else + swSpiTransfer_mode_0(val, SPI_speed); + #endif +} + +static uint8_t swSpiInit(const uint8_t spi_speed) { + #if PIN_EXISTS(LCD_RESET) + SET_OUTPUT(LCD_RESET_PIN); + #endif + SET_OUTPUT(DOGLCD_A0); + OUT_WRITE(DOGLCD_SCK, LOW); + OUT_WRITE(DOGLCD_MOSI, LOW); + OUT_WRITE(DOGLCD_CS, HIGH); + return spi_speed; +} + +uint8_t u8g_com_HAL_HC32_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + switch (msg) { + case U8G_COM_MSG_INIT: + SPI_speed = swSpiInit(LCD_SPI_SPEED); + break; + + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_RESET: + #if PIN_EXISTS(LCD_RESET) + WRITE(LCD_RESET_PIN, arg_val); + #endif + break; + + case U8G_COM_MSG_CHIP_SELECT: + #if U8G_SPI_USE_MODE_3 // This LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + WRITE(DOGLCD_SCK, HIGH); // Set SCK to mode 3 idle state before CS goes active + WRITE(DOGLCD_CS, LOW); + } + else { + WRITE(DOGLCD_CS, HIGH); + WRITE(DOGLCD_SCK, LOW); // Set SCK to mode 0 idle state after CS goes inactive + } + #else + WRITE(DOGLCD_CS, !arg_val); + #endif + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_sw_spi_shift_out(arg_val); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t *ptr = (uint8_t *)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(*ptr++); + arg_val--; + } + } break; + + case U8G_COM_MSG_WRITE_SEQ_P: { + uint8_t *ptr = (uint8_t *)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } break; + + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + WRITE(DOGLCD_A0, arg_val); + break; + } + return 1; +} + +#endif // U8G_SW_SPI_HC32 +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index db43f42eaa..8a9028c8cc 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #ifdef __PLAT_LINUX__ #include "../../inc/MarlinConfig.h" @@ -51,11 +52,55 @@ uint8_t MarlinHAL::active_ch = 0; uint16_t MarlinHAL::adc_value() { const pin_t pin = analogInputToDigitalPin(active_ch); - if (!VALID_PIN(pin)) return 0; - const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); - return data; // return 10bit value as Marlin expects + if (!isValidPin(pin)) return 0; + return uint16_t((Gpio::get(pin) >> 2) & 0x3FF); // return 10bit value as Marlin expects } void MarlinHAL::reboot() { /* Reset the application state and GPIO */ } +// ------------------------ +// BSD String +// ------------------------ + +/** + * Copyright (c) 1998, 2015 Todd C. Miller + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#ifndef HAS_LIBBSD + + /** + * Copy string src to buffer dst of size dsize. At most dsize-1 + * chars will be copied. Always NUL terminates (unless dsize == 0). + * Returns strlen(src); if retval >= dsize, truncation occurred. + */ + size_t MarlinHAL::_strlcpy(char *dst, const char *src, size_t dsize) { + const char *osrc = src; + size_t nleft = dsize; + + // Copy as many bytes as will fit. + if (nleft != 0) while (--nleft != 0) if ((*dst++ = *src++) == '\0') break; + + // Not enough room in dst, add NUL and traverse rest of src. + if (nleft == 0) { + if (dsize != 0) *dst = '\0'; // NUL-terminate dst + while (*src++) { /* nada */ } + } + + return (src - osrc - 1); // count does not include NUL + } + +#endif // HAS_LIBBSD + #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 22c3e521f0..66e4036fdc 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -26,6 +26,11 @@ #include #include #include + +#ifdef HAS_LIBBSD + #include +#endif + #undef min #undef max #include @@ -80,8 +85,8 @@ extern MSerialT usb_serial; #define CRITICAL_SECTION_END() // ADC -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_VREF_MV 5000 +#define HAL_ADC_RESOLUTION 10 // ------------------------ // Class Utilities @@ -119,9 +124,9 @@ public: static void isr_on() {} static void isr_off() {} - static void delay_ms(const int ms) { _delay_ms(ms); } + static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset @@ -162,4 +167,13 @@ public: } static void set_pwm_frequency(const pin_t, int) {} + + #ifndef HAS_LIBBSD + /** + * Redirect missing strlcpy here + */ + static size_t _strlcpy(char *dst, const char *src, size_t dsize); + #define strlcpy hal._strlcpy + #endif + }; diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp index 075b4ccde2..0a09a11091 100644 --- a/Marlin/src/HAL/LINUX/arduino.cpp +++ b/Marlin/src/HAL/LINUX/arduino.cpp @@ -31,10 +31,8 @@ void cli() { } // Disable void sei() { } // Enable // Time functions -void _delay_ms(const int ms) { delay(ms); } - -uint32_t millis() { - return (uint32_t)Clock::millis(); +unsigned long millis() { + return (unsigned long)Clock::millis(); } // This is required for some Arduino libraries we are using @@ -49,28 +47,28 @@ extern "C" void delay(const int msec) { // IO functions // As defined by Arduino INPUT(0x0), OUTPUT(0x1), INPUT_PULLUP(0x2) void pinMode(const pin_t pin, const uint8_t mode) { - if (!VALID_PIN(pin)) return; + if (!isValidPin(pin)) return; Gpio::setMode(pin, mode); } void digitalWrite(pin_t pin, uint8_t pin_status) { - if (!VALID_PIN(pin)) return; + if (!isValidPin(pin)) return; Gpio::set(pin, pin_status); } bool digitalRead(pin_t pin) { - if (!VALID_PIN(pin)) return false; + if (!isValidPin(pin)) return false; return Gpio::get(pin); } void analogWrite(pin_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH - if (!VALID_PIN(pin)) return; + if (!isValidPin(pin)) return; Gpio::set(pin, pwm_value); } uint16_t analogRead(pin_t adc_pin) { - if (!VALID_PIN(DIGITAL_PIN_TO_ANALOG_PIN(adc_pin))) return 0; - return Gpio::get(DIGITAL_PIN_TO_ANALOG_PIN(adc_pin)); + if (!isValidPin(digitalPinToAnalogIndex(adc_pin))) return 0; + return Gpio::get(digitalPinToAnalogIndex(adc_pin)); } char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s) { diff --git a/Marlin/src/HAL/LINUX/eeprom.cpp b/Marlin/src/HAL/LINUX/eeprom.cpp index f878bba6a5..f665600d5e 100644 --- a/Marlin/src/HAL/LINUX/eeprom.cpp +++ b/Marlin/src/HAL/LINUX/eeprom.cpp @@ -35,7 +35,7 @@ uint8_t buffer[MARLIN_EEPROM_SIZE]; char filename[] = "eeprom.dat"; -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { const char eeprom_erase_value = 0xFF; @@ -45,7 +45,7 @@ bool PersistentStore::access_start() { fseek(eeprom_file, 0L, SEEK_END); std::size_t file_size = ftell(eeprom_file); - if (file_size < MARLIN_EEPROM_SIZE) { + if (file_size < long(MARLIN_EEPROM_SIZE)) { memset(buffer + file_size, eeprom_erase_value, MARLIN_EEPROM_SIZE - file_size); } else { diff --git a/Marlin/src/HAL/LINUX/hardware/Timer.cpp b/Marlin/src/HAL/LINUX/hardware/Timer.cpp index 9f0d6a8f3a..013690a404 100644 --- a/Marlin/src/HAL/LINUX/hardware/Timer.cpp +++ b/Marlin/src/HAL/LINUX/hardware/Timer.cpp @@ -37,7 +37,10 @@ Timer::Timer() { } Timer::~Timer() { - timer_delete(timerid); + if (timerid != 0) { + timer_delete(timerid); + timerid = 0; + } } void Timer::init(uint32_t sig_id, uint32_t sim_freq, callback_fn* fn) { diff --git a/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h b/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h index 99a6fc2753..5f1c4b1601 100644 --- a/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h @@ -20,7 +20,3 @@ * */ #pragma once - -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/LINUX." -#endif diff --git a/Marlin/src/HAL/LINUX/inc/Conditionals_type.h b/Marlin/src/HAL/LINUX/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/LINUX/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/LINUX/inc/SanityCheck.h b/Marlin/src/HAL/LINUX/inc/SanityCheck.h index 36d3190a3e..861bade10f 100644 --- a/Marlin/src/HAL/LINUX/inc/SanityCheck.h +++ b/Marlin/src/HAL/LINUX/inc/SanityCheck.h @@ -31,13 +31,17 @@ #endif #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on LINUX." + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported for HAL/LINUX." +#endif + +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for HAL/LINUX." #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on LINUX." + #error "TMC220x Software Serial is not supported for HAL/LINUX." #endif #if ENABLED(POSTMORTEM_DEBUGGING) - #error "POSTMORTEM_DEBUGGING is not yet supported on LINUX." + #error "POSTMORTEM_DEBUGGING is not yet supported for HAL/LINUX." #endif diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index f05aaed880..87148a40b2 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -74,11 +74,10 @@ extern "C" { // Time functions extern "C" void delay(const int ms); -void _delay_ms(const int ms); void delayMicroseconds(unsigned long); -uint32_t millis(); +unsigned long millis(); -//IO functions +// IO functions void pinMode(const pin_t, const uint8_t); void digitalWrite(pin_t, uint8_t); bool digitalRead(pin_t); diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h index cfac5e3b48..9147ef82de 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.h +++ b/Marlin/src/HAL/LINUX/include/pinmapping.h @@ -37,29 +37,29 @@ constexpr uint8_t NUM_ANALOG_INPUTS = 16; constexpr uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS; // Get the digital pin for an analog index -constexpr pin_t analogInputToDigitalPin(const int8_t p) { - return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC); +constexpr pin_t analogInputToDigitalPin(const int8_t a) { + return (WITHIN(a, 0, NUM_ANALOG_INPUTS - 1) ? analog_offset + a : P_NC); } // Get the analog index for a digital pin -constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) { - return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC); +constexpr int8_t digitalPinToAnalogIndex(const pin_t pin) { + return (WITHIN(pin, analog_offset, NUM_DIGITAL_PINS - 1) ? pin - analog_offset : P_NC); } // Return the index of a pin number constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) { return pin; } // Test whether the pin is valid -constexpr bool VALID_PIN(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); } +constexpr bool isValidPin(const pin_t pin) { return WITHIN(pin, 0, NUM_DIGITAL_PINS - 1); } // Test whether the pin is PWM -constexpr bool PWM_PIN(const pin_t p) { return false; } +constexpr bool PWM_PIN(const pin_t) { return false; } // Test whether the pin is interruptible -constexpr bool INTERRUPT_PIN(const pin_t p) { return false; } +constexpr bool INTERRUPT_PIN(const pin_t) { return false; } // Get the pin number at the given index -constexpr pin_t GET_PIN_MAP_PIN(const int16_t ind) { return ind; } +constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) { return pin_t(index); } // Parse a G-code word into a pin index int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); diff --git a/Marlin/src/HAL/LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp index f2af2ff33f..27a066d619 100644 --- a/Marlin/src/HAL/LINUX/main.cpp +++ b/Marlin/src/HAL/LINUX/main.cpp @@ -21,6 +21,7 @@ */ #ifdef __PLAT_LINUX__ +#ifndef UNIT_TEST //#define GPIO_LOGGING // Full GPIO and Positional Logging @@ -135,4 +136,5 @@ int main() { read_serial.join(); } +#endif // UNIT_TEST #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/pinsDebug.h b/Marlin/src/HAL/LINUX/pinsDebug.h index 7bfd97d024..aacb626105 100644 --- a/Marlin/src/HAL/LINUX/pinsDebug.h +++ b/Marlin/src/HAL/LINUX/pinsDebug.h @@ -19,45 +19,62 @@ * along with this program. If not, see . * */ +#pragma once /** - * Support routines for X86_64 + * Pins Debugging for Linux Native + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) */ -/** - * Translation of routines & variables used by pinsDebug.h - */ +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS +#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin -#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define pwm_details(pin) NOOP // (do nothing) -#define pwm_status(pin) false // Print a pin's PWM status. Return true if it's currently a PWM pin. -#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0) -#define digitalRead_mod(p) digitalRead(p) -#define PRINT_PORT(p) -#define GET_ARRAY_PIN(p) pin_array[p].pin -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) -#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin +#define getPinByIndex(x) pin_array[x].pin + +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) // active ADC function/mode/code values for PINSEL registers -constexpr int8_t ADC_pin_mode(pin_t pin) { - return (-1); +constexpr int8_t ADC_pin_mode(const pin_t) { return -1; } + +// The pin and index are the same on this platform +bool getPinIsDigitalByIndex(const pin_t pin) { + return (!isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin)); } -int8_t get_pin_mode(pin_t pin) { - if (!VALID_PIN(pin)) return -1; - return 0; -} +#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0) -bool GET_PINMODE(pin_t pin) { - int8_t pin_mode = get_pin_mode(pin); - if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin +#define digitalRead_mod(P) digitalRead(P) + +int8_t get_pin_mode(const pin_t pin) { return isValidPin(pin) ? 0 : -1; } + +bool getValidPinMode(const pin_t pin) { + const int8_t pin_mode = get_pin_mode(pin); + if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin return false; - return (Gpio::getMode(pin) != 0); //input/output state + return (Gpio::getMode(pin) != 0); // Input/output state } -bool GET_ARRAY_IS_DIGITAL(pin_t pin) { - return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin)); -} +void printPinPWM(const pin_t) {} +bool pwm_status(const pin_t) { return false; } + +void printPinPort(const pin_t) {} + +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0) + +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) diff --git a/Marlin/src/HAL/LINUX/servo_private.h b/Marlin/src/HAL/LINUX/servo_private.h index bcc8d2037f..11e1c2b93c 100644 --- a/Marlin/src/HAL/LINUX/servo_private.h +++ b/Marlin/src/HAL/LINUX/servo_private.h @@ -60,7 +60,6 @@ #define INVALID_SERVO 255 // flag indicating an invalid servo index - // Types typedef struct { diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h index 33136ac9dd..221145e4b3 100644 --- a/Marlin/src/HAL/LINUX/spi_pins.h +++ b/Marlin/src/HAL/LINUX/spi_pins.h @@ -21,22 +21,13 @@ */ #pragma once -#include "../../core/macros.h" -#include "../../inc/MarlinConfigPre.h" - -#if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) - #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently - // needed due to the speed and mode required for communicating with each device being different. - // This requirement can be removed if the SPI access to these devices is updated to use - // spiBeginTransaction. +#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) + #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently + // needed due to the speed and mode required for communicating with each device being different. + // This requirement can be removed if the SPI access to these devices is updated to use + // spiBeginTransaction. #endif -// Onboard SD -//#define SD_SCK_PIN P0_07 -//#define SD_MISO_PIN P0_08 -//#define SD_MOSI_PIN P0_09 -//#define SD_SS_PIN P0_06 - // External SD #ifndef SD_SCK_PIN #define SD_SCK_PIN 50 @@ -47,9 +38,3 @@ #ifndef SD_MOSI_PIN #define SD_MOSI_PIN 52 #endif -#ifndef SD_SS_PIN - #define SD_SS_PIN 53 -#endif -#ifndef SDSS - #define SDSS SD_SS_PIN -#endif diff --git a/Marlin/src/HAL/LINUX/timers.cpp b/Marlin/src/HAL/LINUX/timers.cpp index 66d80f2518..a8ab403197 100644 --- a/Marlin/src/HAL/LINUX/timers.cpp +++ b/Marlin/src/HAL/LINUX/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 2d2a95774c..39c76f02b5 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -33,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals @@ -48,21 +49,20 @@ typedef uint32_t hal_timer_t; #endif #define TEMP_TIMER_RATE 1000000 -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR @@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/LINUX/u8g/LCD_defines.h b/Marlin/src/HAL/LINUX/u8g/LCD_defines.h new file mode 100644 index 0000000000..6caa0240ca --- /dev/null +++ b/Marlin/src/HAL/LINUX/u8g/LCD_defines.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Linux LCD-specific defines + */ diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index 9ff3a6ba59..4b0e255f37 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -23,11 +23,20 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" -#include "../../../gcode/parser.h" +#include "../../core/millis_t.h" -DefaultSerial1 USBSerial(false, UsbSerial); +#include +#include +#include +#include +#include +#include +#include +#include +#include uint32_t MarlinHAL::adc_result = 0; +pin_t MarlinHAL::adc_pin = 0; // U8glib required functions extern "C" { @@ -48,6 +57,133 @@ int freeMemory() { return result; } +extern "C" { + #include + int isLPC1769(); + void disk_timerproc(); +} + +extern uint32_t MSC_SD_Init(uint8_t pdrv); + +void SysTick_Callback() { disk_timerproc(); } + +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); + +void MarlinHAL::init() { + + // Init LEDs + #if PIN_EXISTS(LED) + SET_DIR_OUTPUT(LED_PIN); + WRITE_PIN_CLR(LED_PIN); + #if PIN_EXISTS(LED2) + SET_DIR_OUTPUT(LED2_PIN); + WRITE_PIN_CLR(LED2_PIN); + #if PIN_EXISTS(LED3) + SET_DIR_OUTPUT(LED3_PIN); + WRITE_PIN_CLR(LED3_PIN); + #if PIN_EXISTS(LED4) + SET_DIR_OUTPUT(LED4_PIN); + WRITE_PIN_CLR(LED4_PIN); + #endif + #endif + #endif + + // Flash status LED 3 times to indicate Marlin has started booting + for (uint8_t i = 0; i < 6; ++i) { + TOGGLE(LED_PIN); + delay(100); + } + #endif + + // Init Servo Pins + #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) + #if HAS_SERVO_0 + INIT_SERVO(0); + #endif + #if HAS_SERVO_1 + INIT_SERVO(1); + #endif + #if HAS_SERVO_2 + INIT_SERVO(2); + #endif + #if HAS_SERVO_3 + INIT_SERVO(3); + #endif + #if HAS_SERVO_4 + INIT_SERVO(4); + #endif + #if HAS_SERVO_5 + INIT_SERVO(5); + #endif + + //debug_frmwrk_init(); + //_DBG("\n\nDebug running\n"); + // Initialize the SD card chip select pins as soon as possible + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + + #if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SD_SS_PIN + OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); + #endif + + #ifdef LPC1768_ENABLE_CLKOUT_12M + /** + * CLKOUTCFG register + * bit 8 (CLKOUT_EN) = enables CLKOUT signal. Disabled for now to prevent glitch when enabling GPIO. + * bits 7:4 (CLKOUTDIV) = set to 0 for divider setting of /1 + * bits 3:0 (CLKOUTSEL) = set to 1 to select main crystal oscillator as CLKOUT source + */ + LPC_SC->CLKOUTCFG = (0<<8)|(0<<4)|(1<<0); + // set P1.27 pin to function 01 (CLKOUT) + PINSEL_CFG_Type PinCfg; + PinCfg.Portnum = 1; + PinCfg.Pinnum = 27; + PinCfg.Funcnum = 1; // function 01 (CLKOUT) + PinCfg.OpenDrain = 0; // not open drain + PinCfg.Pinmode = 2; // no pull-up/pull-down + PINSEL_ConfigPin(&PinCfg); + // now set CLKOUT_EN bit + SBI(LPC_SC->CLKOUTCFG, 8); + #endif + + USB_Init(); // USB Initialization + USB_Connect(false); // USB clear connection + delay(1000); // Give OS time to notice + USB_Connect(true); + + TERN_(HAS_SD_HOST_DRIVE, MSC_SD_Init(0)); // Enable USB SD card access + + const millis_t usb_timeout = millis() + 2000; + while (!USB_Configuration && PENDING(millis(), usb_timeout)) { + delay(50); + idletask(); + #if PIN_EXISTS(LED) + TOGGLE(LED_PIN); // Flash quickly during USB initialization + #endif + } + + HAL_timer_init(); + + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler +} + +#include "../../sd/cardreader.h" + +// HAL idle task +void MarlinHAL::idletask() { + #if HAS_SHARED_MEDIA + // When Marlin is using the SD Card it must be locked to prevent PC access via USB. + // For maximum safety we lock the disk if Marlin has it mounted for any reason. + if (card.isMounted()) + MSC_Aquire_Lock(); + else + MSC_Release_Lock(); + #endif + // Perform USB stack housekeeping + MSC_RunDeferredCommands(); +} + void MarlinHAL::reboot() { NVIC_SystemReset(); } uint8_t MarlinHAL::get_reset_source() { @@ -112,6 +248,8 @@ void flashFirmware(const int16_t) { #endif // USE_WATCHDOG +#include "../../../gcode/parser.h" + // For M42/M43, scan command line for pin code // return index into pin map array if found and the pin is valid. // return dval if not found or not a valid pin. diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index b0eeb983b4..052d6637c8 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -38,72 +38,15 @@ extern "C" volatile uint32_t _millis; #include "../shared/math_32bit.h" #include "../shared/HAL_SPI.h" #include "fastio.h" -#include "MarlinSerial.h" #include #include -#include -// ------------------------ -// Serial ports -// ------------------------ +// +// Serial Ports +// -typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; -extern DefaultSerial1 USBSerial; - -#define _MSERIAL(X) MSerial##X -#define MSERIAL(X) _MSERIAL(X) - -#if SERIAL_PORT == -1 - #define MYSERIAL1 USBSerial -#elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL1 MSERIAL(SERIAL_PORT) -#else - #error "SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." -#endif - -#ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == -1 - #define MYSERIAL2 USBSerial - #elif WITHIN(SERIAL_PORT_2, 0, 3) - #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) - #else - #error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB." - #endif -#endif - -#ifdef SERIAL_PORT_3 - #if SERIAL_PORT_3 == -1 - #define MYSERIAL3 USBSerial - #elif WITHIN(SERIAL_PORT_3, 0, 3) - #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) - #else - #error "SERIAL_PORT_3 must be from 0 to 3. You can also use -1 if the board supports Native USB." - #endif -#endif - -#ifdef MMU2_SERIAL_PORT - #if MMU2_SERIAL_PORT == -1 - #define MMU2_SERIAL USBSerial - #elif WITHIN(MMU2_SERIAL_PORT, 0, 3) - #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) - #else - #error "MMU2_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." - #endif -#endif - -#ifdef LCD_SERIAL_PORT - #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL USBSerial - #elif WITHIN(LCD_SERIAL_PORT, 0, 3) - #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) - #else - #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." - #endif - #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.available() - #endif -#endif +#include "MarlinSerial.h" // // Interrupts @@ -127,7 +70,7 @@ extern DefaultSerial1 USBSerial; // K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step // Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels) -#define HAL_ADC_VREF 3.3 // ADC voltage reference +#define HAL_ADC_VREF_MV 3300 // ADC voltage reference #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL @@ -137,12 +80,12 @@ extern DefaultSerial1 USBSerial; // // Test whether the pin is valid -constexpr bool VALID_PIN(const pin_t pin) { +constexpr bool isValidPin(const pin_t pin) { return LPC176x::pin_is_valid(pin); } // Get the analog index for a digital pin -constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t pin) { +constexpr int8_t digitalPinToAnalogIndex(const pin_t pin) { return (LPC176x::pin_is_valid(pin) && LPC176x::pin_has_adc(pin)) ? pin : -1; } @@ -159,13 +102,15 @@ constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) { // Parse a G-code word into a pin index int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card -#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, +#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09 // ------------------------ // Defines // ------------------------ -#define PLATFORM_M997_SUPPORT +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif void flashFirmware(const int16_t); #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment @@ -215,7 +160,7 @@ public: 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() + // Tasks, called from marlin.idle() static void idletask(); // Reset @@ -241,15 +186,18 @@ public: // Begin ADC sampling on the given pin. Called from Temperature::isr! static uint32_t adc_result; - static void adc_start(const pin_t pin) { - adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits - } + static pin_t adc_pin; + + static void adc_start(const pin_t pin) { adc_pin = pin; } // Is the ADC ready for reading? - static bool adc_ready() { return true; } + static bool adc_ready() { return LPC176x::adc_hardware.done(LPC176x::pin_get_adc_channel(adc_pin)); } // The current value of the ADC register - static uint16_t adc_value() { return uint16_t(adc_result); } + static uint16_t adc_value() { + adc_result = FilteredADC::read(adc_pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits + return uint16_t(adc_result); + } /** * Set the PWM duty cycle for the pin to the given value. diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 29f9b43afe..15ace81dc2 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -40,10 +40,6 @@ * SPI sharing pins. The SCK, MOSI & MISO pins can NOT be set/cleared with * WRITE nor digitalWrite when the hardware SPI module within the LPC17xx is * active. If any of these pins are shared then the software SPI must be used. - * - * A more sophisticated hardware SPI can be found at the following link. - * This implementation has not been fully debugged. - * https://github.com/MarlinFirmware/Marlin/tree/071c7a78f27078fd4aee9a3ef365fcf5e143531e */ #ifdef TARGET_LPC1768 @@ -60,7 +56,7 @@ // ------------------------ // Public functions // ------------------------ -#if ENABLED(LPC_SOFTWARE_SPI) +#if ENABLED(SOFTWARE_SPI) // Software SPI @@ -161,7 +157,7 @@ // TODO: Implement this method } -#endif // LPC_SOFTWARE_SPI +#endif // SOFTWARE_SPI /** * @brief Wait until TXE (tx empty) flag is set and BSY (busy) flag unset. @@ -318,8 +314,16 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) { // Enable DMA GPDMA_ChannelCmd(0, ENABLE); + /** + * Observed behaviour on normal data transfer completion (SKR 1.3 board / LPC1768 MCU) + * GPDMA_STAT_INTTC flag is SET + * GPDMA_STAT_INTERR flag is NOT SET + * GPDMA_STAT_RAWINTTC flag is NOT SET + * GPDMA_STAT_RAWINTERR flag is SET + */ + // Wait for data transfer - while (!GPDMA_IntGetStatus(GPDMA_STAT_RAWINTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_RAWINTERR, 0)) { } + while (!GPDMA_IntGetStatus(GPDMA_STAT_INTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_INTERR, 0)) {} // Clear err and int GPDMA_ClearIntPending (GPDMA_STATCLR_INTTC, 0); @@ -333,6 +337,43 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) { SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, DISABLE); } +void SPIClass::dmaSendAsync(void *buf, uint16_t length, bool minc) { + //TODO: LPC dma can only write 0xFFF bytes at once. + GPDMA_Channel_CFG_Type GPDMACfg; + + /* Configure GPDMA channel 0 -------------------------------------------------------------*/ + /* DMA Channel 0 */ + GPDMACfg.ChannelNum = 0; + // Source memory + GPDMACfg.SrcMemAddr = (uint32_t)buf; + // Destination memory - Not used + GPDMACfg.DstMemAddr = 0; + // Transfer size + GPDMACfg.TransferSize = length; + // Transfer width + GPDMACfg.TransferWidth = (_currentSetting->dataSize == DATA_SIZE_16BIT) ? GPDMA_WIDTH_HALFWORD : GPDMA_WIDTH_BYTE; + // Transfer type + GPDMACfg.TransferType = GPDMA_TRANSFERTYPE_M2P; + // Source connection - unused + GPDMACfg.SrcConn = 0; + // Destination connection + GPDMACfg.DstConn = (_currentSetting->spi_d == LPC_SSP0) ? GPDMA_CONN_SSP0_Tx : GPDMA_CONN_SSP1_Tx; + + GPDMACfg.DMALLI = 0; + + // Enable dma on SPI + SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, ENABLE); + + // Only increase memory if minc is true + GPDMACfg.MemoryIncrease = (minc ? GPDMA_DMACCxControl_SI : 0); + + // Setup channel with given parameter + GPDMA_Setup(&GPDMACfg); + + // Enable DMA + GPDMA_ChannelCmd(0, ENABLE); +} + uint16_t SPIClass::read() { return SSP_ReceiveData(_currentSetting->spi_d); } diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp index f2aecf54a0..291eba68a7 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp @@ -25,6 +25,8 @@ #include "../../inc/MarlinConfig.h" +DefaultSerial1 USBSerial(false, UsbSerial); + #if USING_HW_SERIAL0 MarlinSerial _MSerial0(LPC_UART0); MSerialT MSerial0(true, _MSerial0); diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h index 3e6848a1e3..04110e4aff 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -21,6 +21,7 @@ */ #pragma once +#include #include #include @@ -30,14 +31,16 @@ #endif #include "../../core/serial_hook.h" -#ifndef SERIAL_PORT - #define SERIAL_PORT 0 -#endif -#ifndef RX_BUFFER_SIZE - #define RX_BUFFER_SIZE 128 -#endif -#ifndef TX_BUFFER_SIZE - #define TX_BUFFER_SIZE 32 +typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; +extern DefaultSerial1 USBSerial; + +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 3 +#define USB_SERIAL_PORT(...) USBSerial +#include "../shared/serial_ports.h" + +#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.available() #endif class MarlinSerial : public HardwareSerial { diff --git a/Marlin/src/HAL/LPC1768/MinSerial.cpp b/Marlin/src/HAL/LPC1768/MinSerial.cpp index 7a1c038c0b..368bcb5259 100644 --- a/Marlin/src/HAL/LPC1768/MinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MinSerial.cpp @@ -33,18 +33,18 @@ static void TX(char c) { _DBC(c); } void install_min_serial() { HAL_min_serial_out = &TX; } #if DISABLED(DYNAMIC_VECTORTABLE) -extern "C" { - __attribute__((naked)) void JumpHandler_ASM() { - __asm__ __volatile__ ( - "b CommonHandler_ASM\n" - ); + extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); } - void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); -} #endif #endif // POSTMORTEM_DEBUGGING diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index f02f503a67..d7f0a2a555 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -39,7 +39,6 @@ * License along with this library; if not, write to the Free Software * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */ -#pragma once /** * Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers - @@ -50,6 +49,8 @@ #include +#include "../../MarlinCore.h" + class libServo: public Servo { public: void move(const int value) { diff --git a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom/eeprom_flash.cpp similarity index 89% rename from Marlin/src/HAL/LPC1768/eeprom_flash.cpp rename to Marlin/src/HAL/LPC1768/eeprom/eeprom_flash.cpp index 38d2705d51..e24b0fdbc0 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom/eeprom_flash.cpp @@ -36,11 +36,11 @@ * 16Kb I/O buffers (intended to hold DMA USB and Ethernet data, but currently * unused). */ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(FLASH_EEPROM_EMULATION) -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_api.h" extern "C" { #include @@ -61,7 +61,7 @@ static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static bool eeprom_dirty = false; static int current_slot = 0; -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { uint32_t first_nblank_loc, first_nblank_val; @@ -74,7 +74,7 @@ bool PersistentStore::access_start() { if (status == CMD_SUCCESS) { // sector is blank so nothing stored yet - for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EEPROM_ERASE; + for (int i = 0; i < long(MARLIN_EEPROM_SIZE); i++) ram_eeprom[i] = EEPROM_ERASE; current_slot = EEPROM_SLOTS; } else { @@ -82,7 +82,7 @@ bool PersistentStore::access_start() { current_slot = first_nblank_loc / (MARLIN_EEPROM_SIZE); uint8_t *eeprom_data = SLOT_ADDRESS(EEPROM_SECTOR, current_slot); // load current settings - for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i]; + for (int i = 0; i < long(MARLIN_EEPROM_SIZE); i++) ram_eeprom[i] = eeprom_data[i]; } eeprom_dirty = false; @@ -112,7 +112,8 @@ bool PersistentStore::access_finish() { } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { - for (size_t i = 0; i < size; i++) ram_eeprom[pos + i] = value[i]; + const int p = REAL_EEPROM_ADDR(pos); + for (size_t i = 0; i < size; i++) ram_eeprom[p + i] = value[i]; eeprom_dirty = true; crc16(crc, value, size); pos += size; @@ -120,8 +121,9 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui } bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + const int p = REAL_EEPROM_ADDR(pos); const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos]; - if (writing) for (size_t i = 0; i < size; i++) value[i] = ram_eeprom[pos + i]; + if (writing) for (size_t i = 0; i < size; i++) value[i] = ram_eeprom[p + i]; crc16(crc, buff, size); pos += size; return false; // return true for any error diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom/eeprom_sdcard.cpp similarity index 91% rename from Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp rename to Marlin/src/HAL/LPC1768/eeprom/eeprom_sdcard.cpp index 1991d79719..5bf2d353b6 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom/eeprom_sdcard.cpp @@ -26,13 +26,13 @@ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(SDCARD_EEPROM_EMULATION) //#define DEBUG_SD_EEPROM_EMULATION -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_api.h" #include #include @@ -49,10 +49,9 @@ bool eeprom_file_open = false; #define MARLIN_EEPROM_SIZE size_t(0x1000) // 4KiB of Emulated EEPROM #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { - const char eeprom_erase_value = 0xFF; MSC_Aquire_Lock(); if (f_mount(&fat_fs, "", 1)) { MSC_Release_Lock(); @@ -65,6 +64,7 @@ bool PersistentStore::access_start() { UINT bytes_written; FSIZE_t file_size = f_size(&eeprom_file); f_lseek(&eeprom_file, file_size); + const char eeprom_erase_value = 0xFF; while (file_size < capacity() && res == FR_OK) { res = f_write(&eeprom_file, &eeprom_erase_value, 1, &bytes_written); file_size++; @@ -91,15 +91,9 @@ bool PersistentStore::access_finish() { static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) { #if ENABLED(DEBUG_SD_EEPROM_EMULATION) FSTR_P const rw_str = write ? F("write") : F("read"); - SERIAL_CHAR(' '); - SERIAL_ECHOF(rw_str); - SERIAL_ECHOLNPGM("_data(", pos, ",", *value, ",", size, ", ...)"); - if (total) { - SERIAL_ECHOPGM(" f_"); - SERIAL_ECHOF(rw_str); - SERIAL_ECHOPGM("()=", s, "\n size=", size, "\n bytes_"); - SERIAL_ECHOLNF(write ? F("written=") : F("read="), total); - } + SERIAL_ECHOLN(C(' '), rw_str, F("_data("), pos, C(','), *value, C(','), size, F(", ...)")); + if (total) + SERIAL_ECHOLN(F(" f_"), rw_str, F("()="), s, F("\n size="), size, F("\n bytes_"), write ? F("written=") : F("read="), total); else SERIAL_ECHOLNPGM(" f_lseek()=", s); #endif diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom/eeprom_wired.cpp similarity index 89% rename from Marlin/src/HAL/LPC1768/eeprom_wired.cpp rename to Marlin/src/HAL/LPC1768/eeprom/eeprom_wired.cpp index 1bbc39d4a2..6a5d90bd02 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom/eeprom_wired.cpp @@ -21,7 +21,7 @@ */ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if USE_WIRED_EEPROM @@ -30,13 +30,13 @@ * with implementations supplied by the framework. */ -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x8000 // 32K #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } @@ -45,7 +45,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui uint16_t written = 0; while (size--) { uint8_t v = *value; - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes @@ -64,7 +64,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { // Read from external EEPROM - const uint8_t c = eeprom_read_byte((uint8_t*)pos); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/LPC1768/endstop_interrupts.h b/Marlin/src/HAL/LPC1768/endstop_interrupts.h index e4ac17f608..2c75fe6986 100644 --- a/Marlin/src/HAL/LPC1768/endstop_interrupts.h +++ b/Marlin/src/HAL/LPC1768/endstop_interrupts.h @@ -44,147 +44,177 @@ void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) #define LPC1768_PIN_INTERRUPT_M(pin) ((pin >> 0x5 & 0x7) == 0 || (pin >> 0x5 & 0x7) == 2) - #if HAS_X_MAX + #if USE_X_MAX #if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN) #error "X_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MAX_PIN); #endif - #if HAS_X_MIN + #if USE_X_MIN #if !LPC1768_PIN_INTERRUPT_M(X_MIN_PIN) #error "X_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MIN_PIN); #endif - #if HAS_Y_MAX + #if USE_Y_MAX #if !LPC1768_PIN_INTERRUPT_M(Y_MAX_PIN) #error "Y_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MAX_PIN); #endif - #if HAS_Y_MIN + #if USE_Y_MIN #if !LPC1768_PIN_INTERRUPT_M(Y_MIN_PIN) #error "Y_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MIN_PIN); #endif - #if HAS_Z_MAX + #if USE_Z_MAX #if !LPC1768_PIN_INTERRUPT_M(Z_MAX_PIN) #error "Z_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MAX_PIN); #endif - #if HAS_Z_MIN + #if USE_Z_MIN #if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PIN) #error "Z_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PIN); #endif - #if HAS_Z2_MAX + #if USE_X2_MAX + #if !LPC1768_PIN_INTERRUPT_M(X2_MAX_PIN) + #error "X2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X2_MAX_PIN); + #endif + #if USE_X2_MIN + #if !LPC1768_PIN_INTERRUPT_M(X2_MIN_PIN) + #error "X2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X2_MIN_PIN); + #endif + #if USE_Y2_MAX + #if !LPC1768_PIN_INTERRUPT_M(Y2_MAX_PIN) + #error "Y2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y2_MAX_PIN); + #endif + #if USE_Y2_MIN + #if !LPC1768_PIN_INTERRUPT_M(Y2_MIN_PIN) + #error "Y2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y2_MIN_PIN); + #endif + #if USE_Z2_MAX #if !LPC1768_PIN_INTERRUPT_M(Z2_MAX_PIN) #error "Z2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MAX_PIN); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN #if !LPC1768_PIN_INTERRUPT_M(Z2_MIN_PIN) #error "Z2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MIN_PIN); #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX #if !LPC1768_PIN_INTERRUPT_M(Z3_MAX_PIN) #error "Z3_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MAX_PIN); #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN #if !LPC1768_PIN_INTERRUPT_M(Z3_MIN_PIN) #error "Z3_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MIN_PIN); #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX #if !LPC1768_PIN_INTERRUPT_M(Z4_MAX_PIN) #error "Z4_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MAX_PIN); #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN #if !LPC1768_PIN_INTERRUPT_M(Z4_MIN_PIN) #error "Z4_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MIN_PIN); #endif - #if HAS_Z_MIN_PROBE_PIN + #if USE_Z_MIN_PROBE #if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PROBE_PIN) #error "Z_MIN_PROBE_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PROBE_PIN); #endif - #if HAS_I_MAX + #if USE_CALIBRATION + #if !LPC1768_PIN_INTERRUPT_M(CALIBRATION_PIN) + #error "CALIBRATION_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(CALIBRATION_PIN); + #endif + #if USE_I_MAX #if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN) - #error "I_MAX_PIN is not INTERRUPT-capable." + #error "I_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(I_MAX_PIN); - #elif HAS_I_MIN + #elif USE_I_MIN #if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN) - #error "I_MIN_PIN is not INTERRUPT-capable." + #error "I_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(I_MIN_PIN); #endif - #if HAS_J_MAX + #if USE_J_MAX #if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN) - #error "J_MAX_PIN is not INTERRUPT-capable." + #error "J_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(J_MAX_PIN); - #elif HAS_J_MIN + #elif USE_J_MIN #if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN) - #error "J_MIN_PIN is not INTERRUPT-capable." + #error "J_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(J_MIN_PIN); #endif - #if HAS_K_MAX + #if USE_K_MAX #if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN) - #error "K_MAX_PIN is not INTERRUPT-capable." + #error "K_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(K_MAX_PIN); - #elif HAS_K_MIN + #elif USE_K_MIN #if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN) - #error "K_MIN_PIN is not INTERRUPT-capable." + #error "K_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(K_MIN_PIN); #endif - #if HAS_U_MAX + #if USE_U_MAX #if !LPC1768_PIN_INTERRUPT_M(U_MAX_PIN) - #error "U_MAX_PIN is not INTERRUPT-capable." + #error "U_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(U_MAX_PIN); - #elif HAS_U_MIN + #elif USE_U_MIN #if !LPC1768_PIN_INTERRUPT_M(U_MIN_PIN) - #error "U_MIN_PIN is not INTERRUPT-capable." + #error "U_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(U_MIN_PIN); #endif - #if HAS_V_MAX + #if USE_V_MAX #if !LPC1768_PIN_INTERRUPT_M(V_MAX_PIN) - #error "V_MAX_PIN is not INTERRUPT-capable." + #error "V_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(V_MAX_PIN); - #elif HAS_V_MIN + #elif USE_V_MIN #if !LPC1768_PIN_INTERRUPT_M(V_MIN_PIN) - #error "V_MIN_PIN is not INTERRUPT-capable." + #error "V_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(V_MIN_PIN); #endif - #if HAS_W_MAX + #if USE_W_MAX #if !LPC1768_PIN_INTERRUPT_M(W_MAX_PIN) - #error "W_MAX_PIN is not INTERRUPT-capable." + #error "W_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(W_MAX_PIN); - #elif HAS_W_MIN + #elif USE_W_MIN #if !LPC1768_PIN_INTERRUPT_M(W_MIN_PIN) - #error "W_MIN_PIN is not INTERRUPT-capable." + #error "W_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(W_MIN_PIN); #endif diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index 6d2b1a9002..7cb212f5f9 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -26,8 +26,10 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!LPC176x::pin_is_valid(pin)) return; - if (LPC176x::pwm_attach_pin(pin)) - LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range + if (LPC176x::pwm_attach_pin(pin)) { + const uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, LPC176x::pwm_get_period(pin)); + LPC176x::pwm_write(pin, duty); + } } void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { diff --git a/Marlin/src/HAL/LPC1768/fastio.h b/Marlin/src/HAL/LPC1768/fastio.h index c553ffb182..4858334080 100644 --- a/Marlin/src/HAL/LPC1768/fastio.h +++ b/Marlin/src/HAL/LPC1768/fastio.h @@ -66,7 +66,7 @@ #define _WRITE(IO,V) WRITE_PIN(IO,V) /// toggle a pin -#define _TOGGLE(IO) _WRITE(IO, !READ(IO)) +#define _TOGGLE(IO) LPC176x::gpio_toggle(IO) /// set pin as input #define _SET_INPUT(IO) SET_DIR_INPUT(IO) diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h index 32ef908d63..65b019b261 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_FSMC_TFT - #error "Sorry! FSMC TFT displays are not current available for HAL/LPC1768." +#ifndef SERIAL_PORT + #define SERIAL_PORT 0 #endif diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h index 8e7cab185f..9d04c4f787 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h @@ -24,3 +24,10 @@ #if DISABLED(NO_SD_HOST_DRIVE) #define HAS_SD_HOST_DRIVE 1 #endif + +#ifndef RX_BUFFER_SIZE + #define RX_BUFFER_SIZE 128 +#endif +#ifndef TX_BUFFER_SIZE + #define TX_BUFFER_SIZE 32 +#endif diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index be574a96e4..a1b4dd5099 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -23,12 +23,12 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif // LPC1768 boards seem to lose steps when saving to EEPROM during print (issue #20785) // TODO: Which other boards are incompatible? -#if defined(MCU_LPC1768) && PRINTCOUNTER_SAVE_INTERVAL > 0 - #define PRINTCOUNTER_SYNC 1 +#if ALL(MCU_LPC1768, FLASH_EEPROM_EMULATION) && PRINTCOUNTER_SAVE_INTERVAL > 0 + #define PRINTCOUNTER_SYNC #endif diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_type.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 8265d58a6e..5a5617f4ac 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -77,6 +77,10 @@ static_assert(!(NUM_SERVOS && ENABLED(FAST_PWM_FAN)), "BLTOUCH and Servos are in #endif #endif +#if HAS_FSMC_TFT + #error "Sorry! FSMC TFT displays are not current available for HAL/LPC1768." +#endif + static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported on LPC176x."); /** @@ -95,7 +99,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #if USING_HW_SERIAL0 #define IS_TX0(P) (P == P0_02) #define IS_RX0(P) (P == P0_03) - #if IS_TX0(TMC_SW_MISO) || IS_RX0(TMC_SW_MOSI) + #if IS_TX0(TMC_SPI_MISO) || IS_RX0(TMC_SPI_MOSI) #error "Serial port pins (0) conflict with Trinamic SPI pins!" #elif HAS_PRUSA_MMU1 && (IS_TX0(E_MUX1_PIN) || IS_RX0(E_MUX0_PIN)) #error "Serial port pins (0) conflict with Multi-Material-Unit multiplexer pins!" @@ -111,13 +115,13 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #define IS_RX1(P) (P == P0_16) #define _IS_TX1_1 IS_TX1 #define _IS_RX1_1 IS_RX1 - #if IS_TX1(TMC_SW_SCK) + #if IS_TX1(TMC_SPI_SCK) #error "Serial port pins (1) conflict with other pins!" #elif HAS_ROTARY_ENCODER #if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1) #error "Serial port pins (1) conflict with Encoder Buttons!" #elif ANY_TX(1, SD_SCK_PIN, LCD_PINS_D4, DOGLCD_SCK, LCD_RESET_PIN, LCD_PINS_RS, SHIFT_CLK_PIN) \ - || ANY_RX(1, LCD_SDSS, LCD_PINS_RS, SD_MISO_PIN, DOGLCD_A0, SD_SS_PIN, LCD_SDSS, DOGLCD_CS, LCD_RESET_PIN, LCD_BACKLIGHT_PIN) + || ANY_RX(1, LCD_SDSS_PIN, LCD_PINS_RS, SD_MISO_PIN, DOGLCD_A0, SD_SS_PIN, DOGLCD_CS, LCD_RESET_PIN, LCD_BACKLIGHT_PIN) #error "Serial port pins (1) conflict with LCD pins!" #endif #endif @@ -146,7 +150,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "Serial port pins (2) conflict with other pins!" #elif Y_HOME_TO_MIN && IS_TX2(Y_STOP_PIN) #error "Serial port pins (2) conflict with Y endstop pin!" - #elif USES_Z_MIN_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN) + #elif USE_Z_MIN_PROBE && IS_TX2(Z_MIN_PROBE_PIN) #error "Serial port pins (2) conflict with probe pin!" #elif ANY_TX(2, X_ENABLE_PIN, Y_ENABLE_PIN) || ANY_RX(2, X_DIR_PIN, Y_DIR_PIN) #error "Serial port pins (2) conflict with X/Y stepper pins!" @@ -197,7 +201,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #if USEDI2CDEV_M == 0 // P0_27 [D57] (AUX-1) .......... P0_28 [D58] (AUX-1) #define PIN_IS_SDA0(P) (P##_PIN == P0_27) #define IS_SCL0(P) (P == P0_28) - #if ENABLED(SDSUPPORT) && PIN_IS_SDA0(SD_DETECT) + #if HAS_MEDIA && PIN_IS_SDA0(SD_DETECT) #error "SDA0 overlaps with SD_DETECT_PIN!" #elif PIN_IS_SDA0(E0_AUTO_FAN) #error "SDA0 overlaps with E0_AUTO_FAN_PIN!" @@ -207,8 +211,8 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "SCL0 overlaps with Encoder Button!" #elif IS_SCL0(SD_SS_PIN) #error "SCL0 overlaps with SD_SS_PIN!" - #elif IS_SCL0(LCD_SDSS) - #error "SCL0 overlaps with LCD_SDSS!" + #elif IS_SCL0(LCD_SDSS_PIN) + #error "SCL0 overlaps with LCD_SDSS_PIN!" #endif #undef PIN_IS_SDA0 #undef IS_SCL0 @@ -237,7 +241,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #define PIN_IS_SCL2(P) (P##_PIN == P0_11) #if PIN_IS_SDA2(Y_STOP) #error "i2c SDA2 overlaps with Y endstop pin!" - #elif USES_Z_MIN_PROBE_PIN && PIN_IS_SDA2(Z_MIN_PROBE) + #elif USE_Z_MIN_PROBE && PIN_IS_SDA2(Z_MIN_PROBE) #error "i2c SDA2 overlaps with Z probe pin!" #elif PIN_IS_SDA2(X_ENABLE) || PIN_IS_SDA2(Y_ENABLE) #error "i2c SDA2 overlaps with X/Y ENABLE pin!" diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h index 24f4759315..03d34becd8 100644 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ b/Marlin/src/HAL/LPC1768/include/SPI.h @@ -155,6 +155,7 @@ public: void read(uint8_t *buf, uint32_t len); void dmaSend(void *buf, uint16_t length, bool minc); + void dmaSendAsync(void *buf, uint16_t length, bool minc); /** * @brief Sets the number of the SPI peripheral to be used by diff --git a/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c index c489c16e5e..281c920b12 100644 --- a/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c +++ b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c @@ -22,7 +22,7 @@ /** * digipot_mcp4451_I2C_routines.c - * Adapted from https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html + * Adapted from https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html */ #ifdef TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h index 9b6c62b052..4da863389a 100644 --- a/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h +++ b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h @@ -23,7 +23,7 @@ /** * digipot_mcp4451_I2C_routines.h - * Adapted from https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html + * Adapted from https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html */ #ifdef __cplusplus diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp deleted file mode 100644 index 419c99793f..0000000000 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ /dev/null @@ -1,163 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#ifdef TARGET_LPC1768 - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "../../inc/MarlinConfig.h" -#include "../../core/millis_t.h" - -#include "../../sd/cardreader.h" - -extern uint32_t MSC_SD_Init(uint8_t pdrv); - -extern "C" { - #include - extern "C" int isLPC1769(); - extern "C" void disk_timerproc(); -} - -void SysTick_Callback() { disk_timerproc(); } - -TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); - -void MarlinHAL::init() { - - // Init LEDs - #if PIN_EXISTS(LED) - SET_DIR_OUTPUT(LED_PIN); - WRITE_PIN_CLR(LED_PIN); - #if PIN_EXISTS(LED2) - SET_DIR_OUTPUT(LED2_PIN); - WRITE_PIN_CLR(LED2_PIN); - #if PIN_EXISTS(LED3) - SET_DIR_OUTPUT(LED3_PIN); - WRITE_PIN_CLR(LED3_PIN); - #if PIN_EXISTS(LED4) - SET_DIR_OUTPUT(LED4_PIN); - WRITE_PIN_CLR(LED4_PIN); - #endif - #endif - #endif - - // Flash status LED 3 times to indicate Marlin has started booting - LOOP_L_N(i, 6) { - TOGGLE(LED_PIN); - delay(100); - } - #endif - - // Init Servo Pins - #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) - #if HAS_SERVO_0 - INIT_SERVO(0); - #endif - #if HAS_SERVO_1 - INIT_SERVO(1); - #endif - #if HAS_SERVO_2 - INIT_SERVO(2); - #endif - #if HAS_SERVO_3 - INIT_SERVO(3); - #endif - - //debug_frmwrk_init(); - //_DBG("\n\nDebug running\n"); - // Initialize the SD card chip select pins as soon as possible - #if PIN_EXISTS(SD_SS) - OUT_WRITE(SD_SS_PIN, HIGH); - #endif - - #if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SD_SS_PIN - OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); - #endif - - #ifdef LPC1768_ENABLE_CLKOUT_12M - /** - * CLKOUTCFG register - * bit 8 (CLKOUT_EN) = enables CLKOUT signal. Disabled for now to prevent glitch when enabling GPIO. - * bits 7:4 (CLKOUTDIV) = set to 0 for divider setting of /1 - * bits 3:0 (CLKOUTSEL) = set to 1 to select main crystal oscillator as CLKOUT source - */ - LPC_SC->CLKOUTCFG = (0<<8)|(0<<4)|(1<<0); - // set P1.27 pin to function 01 (CLKOUT) - PINSEL_CFG_Type PinCfg; - PinCfg.Portnum = 1; - PinCfg.Pinnum = 27; - PinCfg.Funcnum = 1; // function 01 (CLKOUT) - PinCfg.OpenDrain = 0; // not open drain - PinCfg.Pinmode = 2; // no pull-up/pull-down - PINSEL_ConfigPin(&PinCfg); - // now set CLKOUT_EN bit - SBI(LPC_SC->CLKOUTCFG, 8); - #endif - - USB_Init(); // USB Initialization - USB_Connect(false); // USB clear connection - delay(1000); // Give OS time to notice - USB_Connect(true); - - TERN_(HAS_SD_HOST_DRIVE, MSC_SD_Init(0)); // Enable USB SD card access - - const millis_t usb_timeout = millis() + 2000; - while (!USB_Configuration && PENDING(millis(), usb_timeout)) { - delay(50); - idletask(); - #if PIN_EXISTS(LED) - TOGGLE(LED_PIN); // Flash quickly during USB initialization - #endif - } - - HAL_timer_init(); - - TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler -} - -// HAL idle task -void MarlinHAL::idletask() { - #if HAS_SHARED_MEDIA - // If Marlin is using the SD card we need to lock it to prevent access from - // a PC via USB. - // Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but - // this will not reliably detect delete operations. To be safe we will lock - // the disk if Marlin has it mounted. Unfortunately there is currently no way - // to unmount the disk from the LCD menu. - // if (IS_SD_PRINTING() || IS_SD_FILE_OPEN()) - if (card.isMounted()) - MSC_Aquire_Lock(); - else - MSC_Release_Lock(); - #endif - // Perform USB stack housekeeping - MSC_RunDeferredCommands(); -} - -#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/pinsDebug.h b/Marlin/src/HAL/LPC1768/pinsDebug.h index a2f5c123a2..5baeadd0dd 100644 --- a/Marlin/src/HAL/LPC1768/pinsDebug.h +++ b/Marlin/src/HAL/LPC1768/pinsDebug.h @@ -19,25 +19,35 @@ * along with this program. If not, see . * */ +#pragma once /** - * Support routines for LPC1768 - */ - -/** - * Translation of routines & variables used by pinsDebug.h + * Pins Debugging for LPC1768/9 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) */ #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define pwm_details(pin) pin = pin // do nothing // print PWM details -#define pwm_status(pin) false //Print a pin's PWM status. Return true if it's currently a PWM pin. -#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0) -#define digitalRead_mod(p) extDigitalRead(p) -#define PRINT_PORT(p) -#define GET_ARRAY_PIN(p) pin_array[p].pin -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(pin)); SERIAL_ECHO(buffer); }while(0) +#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0) +#define digitalRead_mod(P) extDigitalRead(P) +#define getPinByIndex(x) pin_array[x].pin +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(P), LPC176x::pin_bit(P)); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(P)); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 17 // space needed to be pretty if not first name assigned to a pin // pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities @@ -45,11 +55,15 @@ #define M43_NEVER_TOUCH(Q) ((Q) == P0_29 || (Q) == P0_30 || (Q) == P2_09) // USB pins #endif -bool GET_PINMODE(const pin_t pin) { - if (!LPC176x::pin_is_valid(pin) || LPC176x::pin_adc_enabled(pin)) // found an invalid pin or active analog pin +bool getValidPinMode(const pin_t pin) { + if (!LPC176x::pin_is_valid(pin) || LPC176x::pin_adc_enabled(pin)) // Invalid pin or active analog pin return false; return LPC176x::gpio_direction(pin); } -#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) +#define getPinIsDigitalByIndex(x) ((bool) pin_array[x].is_digital) + +void printPinPort(const pin_t) {} +void printPinPWM(const pin_t) {} +bool pwm_status(const pin_t) { return false; } diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h index e7d774742f..036bf0e023 100644 --- a/Marlin/src/HAL/LPC1768/spi_pins.h +++ b/Marlin/src/HAL/LPC1768/spi_pins.h @@ -21,21 +21,19 @@ */ #pragma once -#include "../../core/macros.h" - -#if BOTH(SDSUPPORT, HAS_MARLINUI_U8GLIB) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) - #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently - // needed due to the speed and mode required for communicating with each device being different. - // This requirement can be removed if the SPI access to these devices is updated to use - // spiBeginTransaction. +#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) + #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently + // needed due to the speed and mode required for communicating with each device being different. + // This requirement can be removed if the SPI access to these devices is updated to use + // spiBeginTransaction. #endif -/** onboard SD card */ -//#define SD_SCK_PIN P0_07 -//#define SD_MISO_PIN P0_08 -//#define SD_MOSI_PIN P0_09 -//#define SD_SS_PIN P0_06 -/** external */ +// Onboard SD +//#define SD_SCK_PIN P0_07 +//#define SD_MISO_PIN P0_08 +//#define SD_MOSI_PIN P0_09 + +// External SD #ifndef SD_SCK_PIN #define SD_SCK_PIN P0_15 #endif @@ -45,10 +43,3 @@ #ifndef SD_MOSI_PIN #define SD_MOSI_PIN P0_18 #endif -#ifndef SD_SS_PIN - #define SD_SS_PIN P1_23 -#endif -#if !defined(SDSS) || SDSS == P_NC // gets defaulted in pins.h - #undef SDSS - #define SDSS SD_SS_PIN -#endif diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp index a9847b2d2f..beaadaf519 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp @@ -20,15 +20,17 @@ * */ +#ifdef TARGET_LPC1768 + #include "../../../inc/MarlinConfig.h" #if HAS_SPI_TFT #include "tft_spi.h" -SPIClass TFT_SPI::SPIx(1); +SPIClass TFT_SPI::SPIx(TFT_SPI_DEVICE); -void TFT_SPI::Init() { +void TFT_SPI::init() { #if PIN_EXISTS(TFT_RESET) OUT_WRITE(TFT_RESET_PIN, HIGH); delay(100); @@ -38,60 +40,38 @@ void TFT_SPI::Init() { OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif - SET_OUTPUT(TFT_DC_PIN); - SET_OUTPUT(TFT_CS_PIN); - WRITE(TFT_DC_PIN, HIGH); - WRITE(TFT_CS_PIN, HIGH); + OUT_WRITE(TFT_DC_PIN, HIGH); + OUT_WRITE(TFT_CS_PIN, HIGH); - /** - * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz - * STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1 - * so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2 - */ - #if 0 - #if SPI_DEVICE == 1 - #define SPI_CLOCK_MAX SPI_CLOCK_DIV4 - #else - #define SPI_CLOCK_MAX SPI_CLOCK_DIV2 - #endif - uint8_t clock; - uint8_t spiRate = SPI_FULL_SPEED; - switch (spiRate) { - case SPI_FULL_SPEED: clock = SPI_CLOCK_MAX ; break; - case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4 ; break; - case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8 ; break; - case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break; - case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break; - case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break; - default: clock = SPI_CLOCK_DIV2; // Default from the SPI library - } - #endif - - #if TFT_MISO_PIN == BOARD_SPI1_MISO_PIN - SPIx.setModule(1); - #elif TFT_MISO_PIN == BOARD_SPI2_MISO_PIN - SPIx.setModule(2); - #endif + SPIx.setModule(TFT_SPI_DEVICE); SPIx.setClock(SPI_CLOCK_MAX_TFT); SPIx.setBitOrder(MSBFIRST); SPIx.setDataMode(SPI_MODE0); } -void TFT_SPI::DataTransferBegin(uint16_t DataSize) { - SPIx.setDataSize(DataSize); +void TFT_SPI::dataTransferBegin(uint16_t dataSize) { + SPIx.setDataSize(dataSize); SPIx.begin(); WRITE(TFT_CS_PIN, LOW); } -uint32_t TFT_SPI::GetID() { +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + +uint32_t TFT_SPI::getID() { uint32_t id; - id = ReadID(LCD_READ_ID); + id = readID(LCD_READ_ID); if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) - id = ReadID(LCD_READ_ID4); + id = readID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif return id; } -uint32_t TFT_SPI::ReadID(uint16_t Reg) { +uint32_t TFT_SPI::readID(const uint16_t inReg) { uint32_t data = 0; #if PIN_EXISTS(TFT_MISO) @@ -100,31 +80,77 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { SPIx.setClock(SPI_CLOCK_DIV64); SPIx.begin(); WRITE(TFT_CS_PIN, LOW); - WriteReg(Reg); + writeReg(inReg); - LOOP_L_N(i, 4) { + for (uint8_t i = 0; i < 4; ++i) { SPIx.read((uint8_t*)&d, 1); data = (data << 8) | d; } - DataTransferEnd(); + dataTransferEnd(); SPIx.setClock(SPI_CLOCK_MAX_TFT); #endif return data >> 7; } -bool TFT_SPI::isBusy() { return false; } +bool TFT_SPI::isBusy() { + #define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->DMACCSrcAddr != 0) -void TFT_SPI::Abort() { DataTransferEnd(); } + // DMA Channel 0 is hardcoded in dmaSendAsync() and dmaSend() + if (!__IS_DMA_CONFIGURED(LPC_GPDMACH0)) return false; -void TFT_SPI::Transmit(uint16_t Data) { SPIx.transfer(Data); } + if (GPDMA_IntGetStatus(GPDMA_STAT_INTERR, 0)) { + // You should not be here - DMA transfer error flag is set + // Abort DMA transfer and release SPI + } + else { + // Check if DMA transfer completed flag is set + if (!GPDMA_IntGetStatus(GPDMA_STAT_INTTC, 0)) return true; + // Check if SPI TX butter is empty and SPI is idle + if ((SSP_GetStatus(LPC_SSPx, SSP_STAT_TXFIFO_EMPTY) == RESET) || (SSP_GetStatus(LPC_SSPx, SSP_STAT_BUSY) == SET)) return true; + } -void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - DataTransferBegin(DATASIZE_16BIT); - WRITE(TFT_DC_PIN, HIGH); - SPIx.dmaSend(Data, Count, MemoryIncrease); - DataTransferEnd(); + abort(); + return false; +} + +void TFT_SPI::abort() { + // DMA Channel 0 is hardcoded in dmaSendAsync() and dmaSend() + + // Disable DMA + GPDMA_ChannelCmd(0, DISABLE); + + // Clear ERR and TC + GPDMA_ClearIntPending(GPDMA_STATCLR_INTTC, 0); + GPDMA_ClearIntPending(GPDMA_STATCLR_INTERR, 0); + + // Disable DMA on SPI + SSP_DMACmd(LPC_SSPx, SSP_DMA_TX, DISABLE); + + // Deconfigure DMA Channel 0 + LPC_GPDMACH0->DMACCControl = 0U; + LPC_GPDMACH0->DMACCConfig = 0U; + LPC_GPDMACH0->DMACCSrcAddr = 0U; + LPC_GPDMACH0->DMACCDestAddr = 0U; + + dataTransferEnd(); +} + +void TFT_SPI::transmit(uint16_t data) { SPIx.transfer(data); } + +void TFT_SPI::transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + dataTransferBegin(DATASIZE_16BIT); + SPIx.dmaSend(data, count, memoryIncrease); + abort(); +} + +void TFT_SPI::transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + dataTransferBegin(DATASIZE_16BIT); + SPIx.dmaSendAsync(data, count, memoryIncrease); + + TERN_(TFT_SHARED_IO, while (isBusy())); } #endif // HAS_SPI_TFT +#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.h b/Marlin/src/HAL/LPC1768/tft/tft_spi.h index 4753fdbae9..6d5829fc73 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.h +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.h @@ -27,6 +27,18 @@ #include // #include +#define IS_SPI(N) (BOARD_NR_SPI >= N && (TFT_SCK_PIN == BOARD_SPI##N##_SCK_PIN) && (TFT_MOSI_PIN == BOARD_SPI##N##_MOSI_PIN) && (TFT_MISO_PIN == BOARD_SPI##N##_MISO_PIN)) +#if IS_SPI(1) + #define TFT_SPI_DEVICE 1 + #define LPC_SSPx LPC_SSP0 +#elif IS_SPI(2) + #define TFT_SPI_DEVICE 2 + #define LPC_SSPx LPC_SSP1 +#else + #error "Invalid TFT SPI configuration." +#endif +#undef IS_SPI + #ifndef LCD_READ_ID #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) #endif @@ -34,44 +46,44 @@ #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) #endif -#define DATASIZE_8BIT SSP_DATABIT_8 -#define DATASIZE_16BIT SSP_DATABIT_16 -#define TFT_IO_DRIVER TFT_SPI +#define DATASIZE_8BIT SSP_DATABIT_8 +#define DATASIZE_16BIT SSP_DATABIT_16 +#define TFT_IO_DRIVER TFT_SPI +#define DMA_MAX_WORDS 0xFFF -#define DMA_MINC_ENABLE 1 -#define DMA_MINC_DISABLE 0 +#define DMA_MINC_ENABLE 1 +#define DMA_MINC_DISABLE 0 class TFT_SPI { private: - static uint32_t ReadID(uint16_t Reg); - static void Transmit(uint16_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static uint32_t readID(const uint16_t inReg); + static void transmit(uint16_t data); + static void transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count); + static void transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count); public: static SPIClass SPIx; - static void Init(); - static uint32_t GetID(); + static void init(); + static uint32_t getID(); static bool isBusy(); - static void Abort(); + static void abort(); - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT); - static void DataTransferEnd() { OUT_WRITE(TFT_CS_PIN, HIGH); SPIx.end(); }; - static void DataTransferAbort(); + static void dataTransferBegin(uint16_t dataWidth=DATASIZE_16BIT); + static void dataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); SSP_Cmd(LPC_SSPx, DISABLE); }; + static void dataTransferAbort(); - static void WriteData(uint16_t Data) { Transmit(Data); } - static void WriteReg(uint16_t Reg) { OUT_WRITE(TFT_A0_PIN, LOW); Transmit(Reg); OUT_WRITE(TFT_A0_PIN, HIGH); } + static void writeData(uint16_t data) { transmit(data); } + static void writeReg(const uint16_t inReg) { WRITE(TFT_DC_PIN, LOW); transmit(inReg); WRITE(TFT_DC_PIN, HIGH); } - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } - // static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } - static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; - //LPC dma can only write 0xFFF bytes at once. - #define MAX_DMA_SIZE (0xFFF - 1) - while (Count > 0) { - TransmitDMA(DMA_MINC_DISABLE, &Data, Count > MAX_DMA_SIZE ? MAX_DMA_SIZE : Count); - Count = Count > MAX_DMA_SIZE ? Count - MAX_DMA_SIZE : 0; + static void writeSequence_DMA(uint16_t *data, uint16_t count) { transmitDMA(DMA_MINC_ENABLE, data, count); } + static void writeMultiple_DMA(uint16_t color, uint16_t count) { static uint16_t data; data = color; transmitDMA(DMA_MINC_DISABLE, &data, count); } + + static void writeSequence(uint16_t *data, uint16_t count) { transmit(DMA_MINC_ENABLE, data, count); } + static void writeMultiple(uint16_t color, uint32_t count) { + while (count > 0) { + transmit(DMA_MINC_DISABLE, &color, count > DMA_MAX_WORDS ? DMA_MAX_WORDS : count); + count = count > DMA_MAX_WORDS ? count - DMA_MAX_WORDS : 0; } - #undef MAX_DMA_SIZE } }; diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp index 9c1e158981..a737266c68 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp @@ -20,6 +20,8 @@ * */ +#ifdef TARGET_LPC1768 + #include "../../../inc/MarlinConfig.h" #if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS @@ -43,10 +45,12 @@ uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } } #endif -void XPT2046::Init() { - SET_INPUT(TOUCH_MISO_PIN); - SET_OUTPUT(TOUCH_MOSI_PIN); - SET_OUTPUT(TOUCH_SCK_PIN); +void XPT2046::init() { + #if DISABLED(TOUCH_BUTTONS_HW_SPI) + SET_INPUT(TOUCH_MISO_PIN); + SET_OUTPUT(TOUCH_MOSI_PIN); + SET_OUTPUT(TOUCH_SCK_PIN); + #endif OUT_WRITE(TOUCH_CS_PIN, HIGH); #if PIN_EXISTS(TOUCH_INT) @@ -70,9 +74,8 @@ bool XPT2046::isTouched() { ); } -bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { - if (isBusy()) return false; - if (!isTouched()) return false; +bool XPT2046::getRawPoint(int16_t * const x, int16_t * const y) { + if (isBusy() || !isTouched()) return false; *x = getRawData(XPT2046_X); *y = getRawData(XPT2046_Y); return isTouched(); @@ -81,7 +84,7 @@ bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { uint16_t data[3]; - DataTransferBegin(); + dataTransferBegin(); TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.begin()); for (uint16_t i = 0; i < 3 ; i++) { @@ -90,7 +93,7 @@ uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { } TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.end()); - DataTransferEnd(); + dataTransferEnd(); uint16_t delta01 = delta(data[0], data[1]), delta02 = delta(data[0], data[2]), @@ -103,18 +106,18 @@ uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { } uint16_t XPT2046::IO(uint16_t data) { - return TERN(TOUCH_BUTTONS_HW_SPI, HardwareIO, SoftwareIO)(data); + return TERN(TOUCH_BUTTONS_HW_SPI, hardwareIO, softwareIO)(data); } extern uint8_t spiTransfer(uint8_t b); #if ENABLED(TOUCH_BUTTONS_HW_SPI) - uint16_t XPT2046::HardwareIO(uint16_t data) { + uint16_t XPT2046::hardwareIO(uint16_t data) { return SPIx.transfer(data & 0xFF); } #endif -uint16_t XPT2046::SoftwareIO(uint16_t data) { +uint16_t XPT2046::softwareIO(uint16_t data) { uint16_t result = 0; for (uint8_t j = 0x80; j; j >>= 1) { @@ -128,4 +131,5 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) { return result; } -#endif // HAS_TFT_XPT2046 +#endif // HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS +#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.h b/Marlin/src/HAL/LPC1768/tft/xpt2046.h index 7c456cf00e..9a19e3c98d 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.h +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.h @@ -65,12 +65,12 @@ private: static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; - static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; + static void dataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; + static void dataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static uint16_t HardwareIO(uint16_t data); + static uint16_t hardwareIO(uint16_t data); #endif - static uint16_t SoftwareIO(uint16_t data); + static uint16_t softwareIO(uint16_t data); static uint16_t IO(uint16_t data = 0); public: @@ -78,6 +78,6 @@ public: static SPIClass SPIx; #endif - static void Init(); - static bool getRawPoint(int16_t *x, int16_t *y); + static void init(); + static bool getRawPoint(int16_t * const x, int16_t * const y); }; diff --git a/Marlin/src/HAL/LPC1768/timers.cpp b/Marlin/src/HAL/LPC1768/timers.cpp index bbb13f81da..b541ab6e6a 100644 --- a/Marlin/src/HAL/LPC1768/timers.cpp +++ b/Marlin/src/HAL/LPC1768/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index c6d7bc632e..3aec2418d2 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -56,9 +57,9 @@ #define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T) typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) -#define HAL_TIMER_RATE ((F_CPU) / 4) // frequency of timers peripherals +#define HAL_TIMER_RATE ((F_CPU) / 4) // (Hz) Frequency of timers peripherals #ifndef MF_TIMER_STEP #define MF_TIMER_STEP 0 // Timer Index for Stepper @@ -73,22 +74,21 @@ typedef uint32_t hal_timer_t; #define MF_TIMER_PWM 3 // Timer Index for PWM #endif -#define TEMP_TIMER_RATE 1000000 -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_RATE 1000000 // 1MHz +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR @@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp b/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp index e714c3c16d..3fc973e9f5 100644 --- a/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp @@ -21,14 +21,14 @@ */ // adapted from I2C/master/master.c example -// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html +// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html #ifdef TARGET_LPC1768 #include "../include/i2c_util.h" #include "../../../core/millis_t.h" -extern int millis(); +uint32_t millis(); #ifdef __cplusplus extern "C" { diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h index d2260037b6..5b58f1223a 100644 --- a/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h +++ b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h @@ -25,25 +25,22 @@ * LPC1768 LCD-specific defines */ -// The following are optional depending on the platform. +#ifndef U8G_HAL_LINKS -// definitions of HAL specific com and device drivers. -uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); -uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); -uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); -uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); -uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + #define U8G_COM_SSD_I2C_HAL u8g_com_arduino_ssd_i2c_fn // See U8glib-HAL +#else -// connect U8g com generic com names to the desired driver -#define U8G_COM_HW_SPI u8g_com_HAL_LPC1768_hw_spi_fn // use LPC1768 specific hardware SPI routine -#define U8G_COM_SW_SPI u8g_com_HAL_LPC1768_sw_spi_fn // use LPC1768 specific software SPI routine -#define U8G_COM_ST7920_HW_SPI u8g_com_HAL_LPC1768_ST7920_hw_spi_fn -#define U8G_COM_ST7920_SW_SPI u8g_com_HAL_LPC1768_ST7920_sw_spi_fn -#define U8G_COM_SSD_I2C u8g_com_HAL_LPC1768_ssd_hw_i2c_fn + uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); -// let these default for now -#define U8G_COM_PARALLEL u8g_com_null_fn -#define U8G_COM_T6963 u8g_com_null_fn -#define U8G_COM_FAST_PARALLEL u8g_com_null_fn -#define U8G_COM_UC_I2C u8g_com_null_fn + #define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_LPC1768_sw_spi_fn + #define U8G_COM_HAL_HW_SPI_FN u8g_com_HAL_LPC1768_hw_spi_fn + #define U8G_COM_ST7920_HAL_SW_SPI u8g_com_HAL_LPC1768_ST7920_sw_spi_fn + #define U8G_COM_ST7920_HAL_HW_SPI u8g_com_HAL_LPC1768_ST7920_hw_spi_fn + #define U8G_COM_SSD_I2C_HAL u8g_com_HAL_LPC1768_ssd_hw_i2c_fn + +#endif diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c index 466fc80203..51ad7e095b 100644 --- a/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c +++ b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c @@ -27,7 +27,7 @@ * * Couldn't just call exact copies because the overhead killed the LCD update speed * With an intermediate level the softspi was running in the 10-20kHz range which - * resulted in using about about 25% of the CPU's time. + * resulted in using about 25% of the CPU's time. */ #ifdef TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h index d60d93dadd..45e0610fb1 100644 --- a/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h +++ b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h @@ -28,7 +28,7 @@ * * Couldn't just call exact copies because the overhead killed the LCD update speed * With an intermediate level the softspi was running in the 10-20kHz range which - * resulted in using about about 25% of the CPU's time. + * resulted in using about 25% of the CPU's time. */ void u8g_SetPinOutput(uint8_t internal_pin_number); diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp index 0118f92847..406fc4840c 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp @@ -125,5 +125,4 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp index bf76eaf0f4..3dea365ac7 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp @@ -194,5 +194,4 @@ uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_v } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp index ce7b338019..c029dc0680 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp @@ -134,5 +134,4 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp index f116a9b80a..77e5870de7 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp @@ -75,7 +75,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { LPC176x::gpio_set(mosi_pin, !!(b & 0x80)); LPC176x::gpio_set(sck_pin, HIGH); @@ -85,16 +85,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(mosi_pin, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) LPC176x::gpio_set(sck_pin, HIGH); b <<= 1; if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(sck_pin, LOW); } } @@ -104,7 +104,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { LPC176x::gpio_set(sck_pin, LOW); @@ -113,13 +113,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck LPC176x::gpio_set(sck_pin, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) LPC176x::gpio_set(sck_pin, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(mosi_pin, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(sck_pin, HIGH); } b <<= 1; @@ -131,8 +131,8 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck static uint8_t SPI_speed = 0; -static void u8g_sw_spi_HAL_LPC1768_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) +static void u8g_sw_spi_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { + #if U8G_SPI_USE_MODE_3 swSpiTransfer_mode_3(val, SPI_speed, clockPin, -1, dataPin); #else swSpiTransfer_mode_0(val, SPI_speed, clockPin, -1, dataPin); @@ -160,15 +160,15 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, break; case U8G_COM_MSG_CHIP_SELECT: - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + #if U8G_SPI_USE_MODE_3 // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel(u8g, U8G_PI_CS, LOW); } else { u8g_SetPILevel(u8g, U8G_PI_CS, HIGH); - u8g_SetPILevel(u8g, U8G_PI_SCK, 0); // Set SCK to mode 0 idle state after CS goes inactive + u8g_SetPILevel(u8g, U8G_PI_SCK, 0); // Set SCK to mode 0 idle state after CS goes inactive } #else u8g_SetPILevel(u8g, U8G_PI_CS, !arg_val); @@ -176,13 +176,13 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, break; case U8G_COM_MSG_WRITE_BYTE: - u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], arg_val); + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], arg_val); break; case U8G_COM_MSG_WRITE_SEQ: { uint8_t *ptr = (uint8_t *)arg_ptr; while (arg_val > 0) { - u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], *ptr++); + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], *ptr++); arg_val--; } } @@ -191,7 +191,7 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, case U8G_COM_MSG_WRITE_SEQ_P: { uint8_t *ptr = (uint8_t *)arg_ptr; while (arg_val > 0) { - u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], u8g_pgm_read(ptr)); + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], u8g_pgm_read(ptr)); ptr++; arg_val--; } diff --git a/Marlin/src/HAL/LPC1768/upload_extra_script.py b/Marlin/src/HAL/LPC1768/upload_extra_script.py index 3e23c63ca1..6755245436 100755 --- a/Marlin/src/HAL/LPC1768/upload_extra_script.py +++ b/Marlin/src/HAL/LPC1768/upload_extra_script.py @@ -9,127 +9,134 @@ from __future__ import print_function import pioutil if pioutil.is_pio_build(): - target_filename = "FIRMWARE.CUR" - target_drive = "REARM" + target_filename = "FIRMWARE.CUR" + target_drive = "REARM" - import platform + import platform + current_OS = platform.system() - current_OS = platform.system() - Import("env") + env = pioutil.env - def print_error(e): - print('\nUnable to find destination disk (%s)\n' \ - 'Please select it in platformio.ini using the upload_port keyword ' \ - '(https://docs.platformio.org/en/latest/projectconf/section_env_upload.html) ' \ - 'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \ - %(e, env.get('PIOENV'))) + def print_error(e): + print('\nUnable to find destination disk (%s)\n' \ + 'Please select it in platformio.ini using the upload_port keyword ' \ + '(https://docs.platformio.org/en/latest/projectconf/section_env_upload.html) ' \ + 'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \ + %(e, env.get('PIOENV'))) - def before_upload(source, target, env): - try: - from pathlib import Path - # - # Find a disk for upload - # - upload_disk = 'Disk not found' - target_file_found = False - target_drive_found = False - if current_OS == 'Windows': - # - # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:' - # Windows - doesn't care about the disk's name, only cares about the drive letter - import subprocess,string - from ctypes import windll - from pathlib import PureWindowsPath + def before_upload(source, target, env): + try: + from pathlib import Path + # + # Find a disk for upload + # + upload_disk = 'Disk not found' + target_file_found = False + target_drive_found = False + if current_OS == 'Windows': + # + # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:' + # Windows - doesn't care about the disk's name, only cares about the drive letter + import subprocess, string + from ctypes import windll + from pathlib import PureWindowsPath - # getting list of drives - # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python - drives = [] - bitmask = windll.kernel32.GetLogicalDrives() - for letter in string.ascii_uppercase: - if bitmask & 1: - drives.append(letter) - bitmask >>= 1 + # Getting a list of drives + # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-windows-drives + drives = [] + bitmask = windll.kernel32.GetLogicalDrives() + for letter in string.ascii_uppercase: + if bitmask & 1: + drives.append(letter) + bitmask >>= 1 - for drive in drives: - final_drive_name = drive + ':' - # print ('disc check: {}'.format(final_drive_name)) - try: - volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) - except Exception as e: - print ('error:{}'.format(e)) - continue - else: - if target_drive in volume_info and not target_file_found: # set upload if not found target file yet - target_drive_found = True - upload_disk = PureWindowsPath(final_drive_name) - if target_filename in volume_info: - if not target_file_found: - upload_disk = PureWindowsPath(final_drive_name) - target_file_found = True + for drive in drives: + final_drive_name = drive + ':' + # print ('disc check: {}'.format(final_drive_name)) + try: + volume_info = str(subprocess.check_output('cmd /C vol ' + final_drive_name, stderr=subprocess.STDOUT)) + except Exception as e: + print ('error:{}'.format(e)) + continue + else: + if target_drive in volume_info: # set upload + upload_disk = PureWindowsPath(final_drive_name) + target_drive_found = True + break + try: + dir_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) + except Exception as e: + print ('error:{}'.format(e)) + continue + else: + if target_filename in dir_info: + upload_disk = PureWindowsPath(final_drive_name) + target_file_found = True + break - elif current_OS == 'Linux': - # - # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' - # - import getpass - user = getpass.getuser() - mpath = Path('media', user) - drives = [ x for x in mpath.iterdir() if x.is_dir() ] - if target_drive in drives: # If target drive is found, use it. - target_drive_found = True - upload_disk = mpath / target_drive - else: - for drive in drives: - try: - fpath = mpath / drive - files = [ x for x in fpath.iterdir() if x.is_file() ] - except: - continue - else: - if target_filename in files: - upload_disk = mpath / drive - target_file_found = True - break - # - # set upload_port to drive if found - # + elif current_OS == 'Linux': + # + # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' + # + import getpass + user = getpass.getuser() + mpath = Path('/media', user) + drives = [ x for x in mpath.iterdir() if x.is_dir() ] + if target_drive in drives: # If target drive is found, use it. + target_drive_found = True + upload_disk = mpath / target_drive + else: + for drive in drives: + try: + fpath = mpath / drive + filenames = [ x.name for x in fpath.iterdir() if x.is_file() ] + except: + continue + else: + if target_filename in filenames: + upload_disk = mpath / drive + target_file_found = True + break + # + # set upload_port to drive if found + # - if target_file_found or target_drive_found: - env.Replace( - UPLOAD_FLAGS="-P$UPLOAD_PORT" - ) + if target_file_found or target_drive_found: + env.Replace( + UPLOAD_FLAGS="-P$UPLOAD_PORT" + ) - elif current_OS == 'Darwin': # MAC - # - # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' - # - dpath = Path('/Volumes') # human readable names - drives = [ x for x in dpath.iterdir() ] - if target_drive in drives and not target_file_found: # set upload if not found target file yet - target_drive_found = True - upload_disk = dpath / target_drive - for drive in drives: - try: - fpath = dpath / drive # will get an error if the drive is protected - files = [ x for x in fpath.iterdir() ] - except: - continue - else: - if target_filename in files: - if not target_file_found: - upload_disk = dpath / drive - target_file_found = True + elif current_OS == 'Darwin': # MAC + # + # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' + # + dpath = Path('/Volumes') # human readable names + drives = [ x for x in dpath.iterdir() if x.is_dir() ] + if target_drive in drives and not target_file_found: # set upload if not found target file yet + target_drive_found = True + upload_disk = dpath / target_drive + for drive in drives: + try: + fpath = dpath / drive # will get an error if the drive is protected + filenames = [ x.name for x in fpath.iterdir() if x.is_file() ] + except: + continue + else: + if target_filename in filenames: + upload_disk = dpath / drive + target_file_found = True + break - # - # Set upload_port to drive if found - # - if target_file_found or target_drive_found: - env.Replace(UPLOAD_PORT=str(upload_disk)) - print('\nUpload disk: ', upload_disk, '\n') - else: - print_error('Autodetect Error') + # + # Set upload_port to drive if found + # + if target_file_found or target_drive_found: + env.Replace(UPLOAD_PORT=str(upload_disk)) + print('\nUpload disk: ', upload_disk, '\n') + else: + print_error('Autodetect Error') - except Exception as e: - print_error(str(e)) + except Exception as e: + print_error(str(e)) - env.AddPreAction("upload", before_upload) + env.AddPreAction("upload", before_upload) diff --git a/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf b/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf index 4732eb8552..37d9a617db 100644 --- a/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf +++ b/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf @@ -8,14 +8,12 @@ DriverVer =04/14/2008, 5.1.2600.5512 [Manufacturer] %PROVIDER%=DeviceList,ntamd64 - [DeviceList] %DESCRIPTION%=LPC1768USB, USB\VID_1D50&PID_6029&MI_00 [DeviceList.ntamd64] %DESCRIPTION%=LPC1768USB, USB\VID_1D50&PID_6029&MI_00 - [LPC1768USB] include=mdmcpq.inf CopyFiles=FakeModemCopyFileSection @@ -28,9 +26,8 @@ AddService=usbser, 0x00000002, LowerFilter_Service_Inst [SerialPropPageAddReg] HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider" - [Strings] PROVIDER = "marlinfw.org" DRIVER.SVC = "Marlin USB Driver" DESCRIPTION= "Marlin USB Serial" -COMPOSITE = "Marlin USB VCOM" \ No newline at end of file +COMPOSITE = "Marlin USB VCOM" diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.cpp b/Marlin/src/HAL/NATIVE_SIM/HAL.cpp new file mode 100644 index 0000000000..18c225fb3f --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.cpp @@ -0,0 +1,67 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Copyright (c) 1998, 2015 Todd C. Miller + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#ifndef HAS_LIBBSD + + #include "HAL.h" + + /** + * Copy string src to buffer dst of size dsize. At most dsize-1 + * chars will be copied. Always NUL terminates (unless dsize == 0). + * Returns strlen(src); if retval >= dsize, truncation occurred. + */ + size_t MarlinHAL::_strlcpy(char *dst, const char *src, size_t dsize) { + const char *osrc = src; + size_t nleft = dsize; + + // Copy as many bytes as will fit. + if (nleft != 0) while (--nleft != 0) if ((*dst++ = *src++) == '\0') break; + + // Not enough room in dst, add NUL and traverse rest of src. + if (nleft == 0) { + if (dsize != 0) *dst = '\0'; // NUL-terminate dst + while (*src++) { /* nada */ } + } + + return (src - osrc - 1); // count does not include NUL + } + +#endif // HAS_LIBBSD +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 6620361144..b3b66d54d3 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -52,7 +52,9 @@ uint8_t _getc(); // ------------------------ #define CPU_32_BIT -#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +class Servo; +typedef Servo hal_servo_t; #define F_CPU 100000000 #define SystemCoreClock F_CPU @@ -71,37 +73,10 @@ extern MSerialT serial_stream_2; extern MSerialT serial_stream_3; #define _MSERIAL(X) serial_stream_##X -#define MSERIAL(X) _MSERIAL(X) -#if WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL1 MSERIAL(SERIAL_PORT) -#else - #error "SERIAL_PORT must be from 0 to 3. Please update your configuration." -#endif - -#ifdef SERIAL_PORT_2 - #if WITHIN(SERIAL_PORT_2, 0, 3) - #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) - #else - #error "SERIAL_PORT_2 must be from 0 to 3. Please update your configuration." - #endif -#endif - -#ifdef MMU2_SERIAL_PORT - #if WITHIN(MMU2_SERIAL_PORT, 0, 3) - #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) - #else - #error "MMU2_SERIAL_PORT must be from 0 to 3. Please update your configuration." - #endif -#endif - -#ifdef LCD_SERIAL_PORT - #if WITHIN(LCD_SERIAL_PORT, 0, 3) - #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) - #else - #error "LCD_SERIAL_PORT must be from 0 to 3. Please update your configuration." - #endif -#endif +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 3 +#include "../shared/serial_ports.h" // ------------------------ // Interrupts @@ -114,8 +89,8 @@ extern MSerialT serial_stream_3; // ADC // ------------------------ -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_VREF_MV 5000 +#define HAL_ADC_RESOLUTION 10 /* ---------------- Delay in cycles */ @@ -208,8 +183,8 @@ public: MarlinHAL() {} // Watchdog - static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); - static void watchdog_refresh() IF_DISABLED(USE_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() @@ -220,9 +195,9 @@ public: static void isr_on() {} static void isr_off() {} - static void delay_ms(const int ms) { _delay_ms(ms); } + static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset @@ -259,8 +234,20 @@ public: * No option to invert the duty cycle [default = false] * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false) { + auto value = map(v, 0, v_size, 0, UINT16_MAX); + value = invert ? UINT16_MAX - value : value; + analogWrite(pin, value); } + static void set_pwm_frequency(const pin_t, int) {} + + #ifndef HAS_LIBBSD + /** + * Redirect missing strlcpy here + */ + static size_t _strlcpy(char *dst, const char *src, size_t dsize); + #define strlcpy hal._strlcpy + #endif + }; diff --git a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h index b5cc6f02a4..0c447ba4cb 100644 --- a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h +++ b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/NATIVE_SIM/Servo.cpp b/Marlin/src/HAL/NATIVE_SIM/Servo.cpp new file mode 100644 index 0000000000..a15eda1bf6 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/Servo.cpp @@ -0,0 +1,104 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_NATIVE_SIM__ + +#include "../../inc/MarlinConfig.h" + +#if HAS_SERVOS + +#include "Servo.h" + +//#define DEBUG_SERVOS +#define DEBUG_OUT ENABLED(DEBUG_SERVOS) +#include "../../../core/debug_out.h" + +uint8_t ServoCount = 0; // the total number of attached servos + +Servo::Servo() { + // Constructor stub + DEBUG_ECHOLNPGM("Debug Servo: constructor"); + this->servoIndex = ServoCount++; // assign a servo index to this instance +} + +uint8_t Servo::attach(int pin) { + // Attach stub + DEBUG_ECHOLNPGM("Debug Servo: attach to pin ", pin, " servo index ", this->servoIndex); + return attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH); +} + +uint8_t Servo::attach(int pin, int min, int max) { + // Attach with min and max stub + DEBUG_ECHOLNPGM("Debug Servo: attach to pin ", pin, " with min ", min, " and max ", max); + if (pin > 0) servo_pin = pin; + return this->servoIndex; +} + +void Servo::detach() { + // Detach stub + DEBUG_ECHOLNPGM("Debug Servo: detach"); +} + +// If value is < 200 it is treated as an angle, otherwise as pulse width in microseconds +void Servo::write(int value) { + if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds) + value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN_US(min), SERVO_MAX_US(max)); + } + writeMicroseconds(value); + DEBUG_ECHOLNPGM("Debug Servo: write ", value); +} + +void Servo::writeMicroseconds(int value) { + // Simulate the servo movement + this->value = value; + hal.set_pwm_duty(pin_t(this->servo_pin), (float(value) / 20000) * UINT16_MAX, UINT16_MAX); + DEBUG_ECHOLNPGM("Debug Servo: write microseconds ", value); +} + +int Servo::read() { + // Read stub + DEBUG_ECHOLNPGM("Debug Servo: read ", this->value); + return this->value; +} + +int Servo::readMicroseconds() { + // Read microseconds stub + DEBUG_ECHOLNPGM("Debug Servo: read microseconds"); + return 0; +} + +bool Servo::attached() { + // Attached stub + DEBUG_ECHOLNPGM("Debug Servo: attached"); + return false; +} + +int Servo::move(const unsigned char cmd) { + // Move stub + DEBUG_ECHOLNPGM("Debug Servo: move ", cmd); + write(cmd); + return 0; +} + +#endif // HAS_SERVOS +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/Servo.h b/Marlin/src/HAL/NATIVE_SIM/Servo.h new file mode 100644 index 0000000000..428871142c --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/Servo.h @@ -0,0 +1,48 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo +#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo +#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached +#define SERVO_MIN_US(v) (MIN_PULSE_WIDTH - (v) * 4) // minimum value in uS for this servo +#define SERVO_MAX_US(v) (MAX_PULSE_WIDTH - (v) * 4) // maximum value in uS for this servo + +class Servo { +public: + Servo(); + uint8_t attach(int pin); // Attach the given pin to the next free channel, set pinMode, return channel number or INVALID_SERVO if failure + uint8_t attach(int pin, int min, int max); // As above but also set min and max values for writes. + void detach(); + void write(int value); // If value is < 200 it's treated as an angle, otherwise as pulse width in microseconds + void writeMicroseconds(int value); // Write pulse width in microseconds + int read(); // Return current pulse width as an angle between 0 and 180 degrees + int readMicroseconds(); // Return current pulse width in microseconds for this servo + bool attached(); // Return true if this servo is attached, otherwise false + int move (const unsigned char cmd); +private: + uint8_t servoIndex; // Index into the channel data for this servo + int8_t min; // Minimum is this value times 4 added to MIN_PULSE_WIDTH + int8_t max; // Maximum is this value times 4 added to MAX_PULSE_WIDTH + int value; // Pulse width in microseconds for this servo + int servo_pin = 0; // pin number for this servo +}; diff --git a/Marlin/src/HAL/NATIVE_SIM/endstop_interrupts.h b/Marlin/src/HAL/NATIVE_SIM/endstop_interrupts.h new file mode 100644 index 0000000000..e74c312274 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/endstop_interrupts.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +#error "ENDSTOP_INTERRUPTS_FEATURE is not supported in this simulation environment." + +void setup_endstop_interrupts() { + // This function is a stub for setting up endstop interrupts. + // Since this is a simulation environment, actual hardware interrupts + // are not applicable. Add any necessary simulation-specific logic here. +} diff --git a/Marlin/src/HAL/NATIVE_SIM/fastio.h b/Marlin/src/HAL/NATIVE_SIM/fastio.h index de8013b1e5..e0b7af09f9 100644 --- a/Marlin/src/HAL/NATIVE_SIM/fastio.h +++ b/Marlin/src/HAL/NATIVE_SIM/fastio.h @@ -28,6 +28,8 @@ #include "../shared/Marduino.h" #include +#define NO_COMPILE_TIME_PWM + #define SET_DIR_INPUT(IO) Gpio::setDir(IO, 1) #define SET_DIR_OUTPUT(IO) Gpio::setDir(IO, 0) @@ -44,7 +46,7 @@ * * Now you can simply SET_OUTPUT(STEP); WRITE(STEP, HIGH); WRITE(STEP, LOW); * - * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html + * Why double up on these macros? see https://gcc.gnu.org/onlinedocs/cpp/Stringification.html */ /// Read a pin diff --git a/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_type.h b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h b/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h index 2d7bef23a3..615e5254c9 100644 --- a/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h +++ b/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h @@ -31,7 +31,7 @@ #endif #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on LINUX." + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported for HAL/LINUX." #endif #if HAS_TMC_SW_SERIAL diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp new file mode 100644 index 0000000000..1354c79b31 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp @@ -0,0 +1,49 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../../inc/MarlinConfig.h" +#include "pinsDebug.h" + +int8_t ADC_pin_mode(const pin_t) { return -1; } + +int8_t get_pin_mode(const pin_t pin) { return isValidPin(pin) ? 0 : -1; } + +bool getValidPinMode(const pin_t pin) { + const int8_t pin_mode = get_pin_mode(pin); + if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin + return false; + + return (Gpio::getMode(pin) != 0); // Input/output state +} + +// The pin and index are the same on this platform +bool getPinIsDigitalByIndex(const pin_t pin) { + return !isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin); +} + +void printPinPort(const pin_t) {} +void printPinPWM(const pin_t) {} +bool pwm_status(const pin_t) { return false; } + +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h index aa90eb39a3..752802d438 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -2,6 +2,9 @@ * Marlin 3D Printer Firmware * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or @@ -16,46 +19,43 @@ * along with this program. If not, see . * */ - -/** - * Support routines for X86_64 - */ #pragma once /** - * Translation of routines & variables used by pinsDebug.h + * Pins Debugging for x86_64 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) */ #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define pwm_details(pin) pin = pin // do nothing // print PWM details -#define pwm_status(pin) false //Print a pin's PWM status. Return true if it's currently a PWM pin. -#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0) -#define digitalRead_mod(p) digitalRead(p) -#define PRINT_PORT(p) -#define GET_ARRAY_PIN(p) pin_array[p].pin -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) +#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL)) +#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0) +#define digitalRead_mod(P) digitalRead(P) +#define getPinByIndex(x) pin_array[x].pin +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin -// active ADC function/mode/code values for PINSEL registers -inline constexpr int8_t ADC_pin_mode(pin_t pin) { - return (-1); -} - -inline int8_t get_pin_mode(pin_t pin) { - if (!VALID_PIN(pin)) return -1; - return 0; -} - -inline bool GET_PINMODE(pin_t pin) { - int8_t pin_mode = get_pin_mode(pin); - if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin - return false; - - return (Gpio::getMode(pin) != 0); //input/output state -} - -inline bool GET_ARRAY_IS_DIGITAL(pin_t pin) { - return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin)); -} +// Active ADC function/mode/code values for PINSEL registers +int8_t ADC_pin_mode(const pin_t); +int8_t get_pin_mode(const pin_t); +bool getValidPinMode(const pin_t); +bool getPinIsDigitalByIndex(const pin_t); +void printPinPort(const pin_t); +void printPinPWM(const pin_t); +bool pwm_status(const pin_t); diff --git a/Marlin/src/HAL/NATIVE_SIM/servo_private.h b/Marlin/src/HAL/NATIVE_SIM/servo_private.h deleted file mode 100644 index 06be1893f6..0000000000 --- a/Marlin/src/HAL/NATIVE_SIM/servo_private.h +++ /dev/null @@ -1,80 +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 - -/** - * servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2 - * Copyright (c) 2009 Michael Margolis. All right reserved. - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - */ - -/** - * Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers - - * Version 2 Copyright (c) 2009 Michael Margolis. All right reserved. - * - * The only modification was to update/delete macros to match the LPC176x. - * - */ - -#include - -// Macros -//values in microseconds -#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo -#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo -#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached -#define REFRESH_INTERVAL 20000 // minimum time to refresh servos in microseconds - -#define MAX_SERVOS 4 - -#define INVALID_SERVO 255 // flag indicating an invalid servo index - - -// Types - -typedef struct { - uint8_t nbr : 8 ; // a pin number from 0 to 254 (255 signals invalid pin) - uint8_t isActive : 1 ; // true if this channel is enabled, pin not pulsed if false -} ServoPin_t; - -typedef struct { - ServoPin_t Pin; - unsigned int pulse_width; // pulse width in microseconds -} ServoInfo_t; - -// Global variables - -extern uint8_t ServoCount; -extern ServoInfo_t servo_info[MAX_SERVOS]; diff --git a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h index a5138e0ccb..0e83e13692 100644 --- a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h +++ b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h @@ -21,11 +21,8 @@ */ #pragma once -#include "../../core/macros.h" -#include "../../inc/MarlinConfigPre.h" - -#if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) - #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently +#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) + #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use // spiBeginTransaction. @@ -35,7 +32,6 @@ //#define SD_SCK_PIN P0_07 //#define SD_MISO_PIN P0_08 //#define SD_MOSI_PIN P0_09 -//#define SD_SS_PIN P0_06 // External SD #ifndef SD_SCK_PIN @@ -47,9 +43,3 @@ #ifndef SD_MOSI_PIN #define SD_MOSI_PIN 52 #endif -#ifndef SD_SS_PIN - #define SD_SS_PIN 53 -#endif -#ifndef SDSS - #define SDSS SD_SS_PIN -#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h index b3e622f19a..944b8267f6 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h @@ -31,34 +31,37 @@ #endif #define DATASIZE_8BIT 8 -#define DATASIZE_16BIT 16 -#define TFT_IO_DRIVER TFT_SPI +#define DATASIZE_16BIT 16 +#define TFT_IO_DRIVER TFT_SPI +#define DMA_MAX_WORDS 0xFFFF -#define DMA_MINC_ENABLE 1 +#define DMA_MINC_ENABLE 1 #define DMA_MINC_DISABLE 0 class TFT_SPI { private: - static uint32_t ReadID(uint16_t Reg); - static void Transmit(uint16_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static uint32_t readID(const uint16_t inReg); + static void transmit(uint16_t data); + static void transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count); public: // static SPIClass SPIx; - static void Init(); - static uint32_t GetID(); + static void init(); + static uint32_t getID(); static bool isBusy(); - static void Abort(); + static void abort(); - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT); - static void DataTransferEnd(); - static void DataTransferAbort(); + static void dataTransferBegin(uint16_t dataWidth=DATASIZE_16BIT); + static void dataTransferEnd(); + static void dataTransferAbort(); - static void WriteData(uint16_t Data); - static void WriteReg(uint16_t Reg); + static void writeData(uint16_t data); + static void writeReg(const uint16_t inReg); - static void WriteSequence(uint16_t *Data, uint16_t Count); - // static void WriteMultiple(uint16_t Color, uint16_t Count); - static void WriteMultiple(uint16_t Color, uint32_t Count); + static void writeSequence_DMA(uint16_t *data, uint16_t count) { writeSequence(data, count); } + static void writeMultiple_DMA(uint16_t color, uint16_t count) { writeMultiple(color, count); } + + static void writeSequence(uint16_t *data, uint16_t count); + static void writeMultiple(uint16_t color, uint32_t count); }; diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h index b131853643..d37f74c774 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h @@ -2,6 +2,9 @@ * Marlin 3D Printer Firmware * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or @@ -51,7 +54,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif @@ -62,12 +65,12 @@ private: static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static void DataTransferBegin(); - static void DataTransferEnd(); + static void dataTransferBegin(); + static void dataTransferEnd(); #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static uint16_t HardwareIO(uint16_t data); + static uint16_t hardwareIO(uint16_t data); #endif - static uint16_t SoftwareIO(uint16_t data); + static uint16_t softwareIO(uint16_t data); static uint16_t IO(uint16_t data = 0); public: @@ -75,6 +78,6 @@ public: static SPIClass SPIx; #endif - static void Init(); - static bool getRawPoint(int16_t *x, int16_t *y); + static void init(); + static bool getRawPoint(int16_t * const x, int16_t * const y); }; diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index be38d583b6..be59bb8676 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -33,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint64_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX) #define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals @@ -51,22 +52,21 @@ typedef uint64_t hal_timer_t; #endif #define SYSTICK_TIMER_FREQUENCY 1000 -#define TEMP_TIMER_RATE 1000000 -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_RATE 1'000'000 // (Hz) Temperature Timer count rate +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR call frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR @@ -87,5 +87,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp index 745454394a..8033b79e3d 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp @@ -21,7 +21,7 @@ */ // adapted from I2C/master/master.c example -// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html +// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html #ifdef __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h index 6d5f91d3ba..ec263b6dd3 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h @@ -34,4 +34,3 @@ void u8g_i2c_stop(); #ifdef __cplusplus } #endif - diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h index 44ffbfeb90..63701ca334 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h @@ -21,24 +21,14 @@ */ #pragma once -void usleep(uint64_t microsec); -// The following are optional depending on the platform. +/** + * Native/Simulator LCD-specific defines + */ + +void usleep(uint64_t microsec); -// definitions of HAL specific com and device drivers. uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); -// connect U8g com generic com names to the desired driver -#define U8G_COM_SW_SPI u8g_com_sw_spi_fn -#define U8G_COM_ST7920_SW_SPI u8g_com_ST7920_sw_spi_fn - -// let these default for now -#define U8G_COM_HW_SPI u8g_com_null_fn -#define U8G_COM_ST7920_HW_SPI u8g_com_null_fn -#define U8G_COM_SSD_I2C u8g_com_null_fn -#define U8G_COM_PARALLEL u8g_com_null_fn -#define U8G_COM_T6963 u8g_com_null_fn -#define U8G_COM_FAST_PARALLEL u8g_com_null_fn -#define U8G_COM_UC_I2C u8g_com_null_fn - - +#define U8G_COM_HAL_SW_SPI_FN u8g_com_sw_spi_fn +#define U8G_COM_ST7920_HAL_SW_SPI u8g_com_ST7920_sw_spi_fn 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 91b7e0f67f..9cb33694a3 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp @@ -27,7 +27,7 @@ * * Couldn't just call exact copies because the overhead killed the LCD update speed * With an intermediate level the softspi was running in the 10-20kHz range which - * resulted in using about about 25% of the CPU's time. + * resulted in using about 25% of the CPU's time. */ #ifdef __PLAT_NATIVE_SIM__ @@ -43,7 +43,6 @@ void u8g_SetPinOutput(uint8_t internal_pin_number) { SET_DIR_OUTPUT(internal_pin 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 } diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h index c27c84e8c3..ab73635d28 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h @@ -28,10 +28,9 @@ * * Couldn't just call exact copies because the overhead killed the LCD update speed * With an intermediate level the softspi was running in the 10-20kHz range which - * resulted in using about about 25% of the CPU's time. + * resulted in using about 25% of the CPU's time. */ - #ifdef __cplusplus extern "C" { #endif diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp index c384cdd751..b07bc1644d 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp @@ -71,13 +71,13 @@ static uint8_t SPI_speed = 0; static uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) { for (uint8_t i = 0; i < 8; i++) { - WRITE_PIN(mosi_pin, !!(b & 0x80)); + WRITE_PIN(sck_pin, TERN(U8G_SPI_USE_MODE_3, LOW, HIGH)); DELAY_CYCLES(SPI_SPEED); - WRITE_PIN(sck_pin, HIGH); + WRITE_PIN(mosi_pin, !!(b & 0x80)); DELAY_CYCLES(SPI_SPEED); b <<= 1; if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; - WRITE_PIN(sck_pin, LOW); + WRITE_PIN(sck_pin, TERN(U8G_SPI_USE_MODE_3, HIGH, LOW)); DELAY_CYCLES(SPI_SPEED); } return b; @@ -85,7 +85,7 @@ static uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck static uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) { WRITE_PIN(mosi_pin, HIGH); - WRITE_PIN(sck_pin, LOW); + WRITE_PIN(sck_pin, TERN(U8G_SPI_USE_MODE_3, HIGH, LOW)); return spiRate; } @@ -93,13 +93,14 @@ static void u8g_com_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) { static uint8_t rs_last_state = 255; if (rs != rs_last_state) { // Transfer Data (FA) or Command (F8) - swSpiTransfer(rs ? 0x0FA : 0x0F8, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); + swSpiTransfer(rs ? 0xFA : 0xF8, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); rs_last_state = rs; DELAY_US(40); // Give the controller time to process the data: 20 is bad, 30 is OK, 40 is safe } - swSpiTransfer(val & 0x0F0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); + swSpiTransfer(val & 0xF0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); swSpiTransfer(val << 4, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); } + #ifdef __cplusplus extern "C" { #endif @@ -128,7 +129,7 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void break; case U8G_COM_MSG_RESET: - if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ @@ -163,9 +164,37 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void } return 1; } + #ifdef __cplusplus } #endif +#if ENABLED(LIGHTWEIGHT_UI) + + #define ST7920_CS() { WRITE(LCD_PINS_RS, HIGH); } + #define ST7920_NCS() { WRITE(LCD_PINS_RS, LOW); } + #define ST7920_SET_CMD() { ST7920_SWSPI_SND_8BIT(0xF8); } + #define ST7920_SET_DAT() { ST7920_SWSPI_SND_8BIT(0xFA); } + #define ST7920_WRITE_BYTE(a) { ST7920_SWSPI_SND_8BIT((uint8_t)((a)&0xF0u)); ST7920_SWSPI_SND_8BIT((uint8_t)((a)<<4U)); } + + #define ST7920_DAT(V) !!((V) & 0x80) + + #define ST7920_SND_BIT(...) do{ \ + WRITE(LCD_PINS_D4, LOW); \ + WRITE(LCD_PINS_EN, ST7920_DAT(val)); \ + WRITE(LCD_PINS_D4, HIGH); \ + val <<= 1; }while(0); + + void ST7920_SWSPI_SND_8BIT(uint8_t val) { + REPEAT(8, ST7920_SND_BIT); + } + + void ST7920_cs() { ST7920_CS(); } + void ST7920_ncs() { ST7920_NCS(); } + void ST7920_set_cmd() { ST7920_SET_CMD(); } + void ST7920_set_dat() { ST7920_SET_DAT(); } + void ST7920_write_byte(const uint8_t val) { ST7920_WRITE_BYTE(val); } +#endif // LIGHTWEIGHT_UI + #endif // IS_U8GLIB_ST7920 -#endif // TARGET_LPC1768 +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp index 7be84580b1..fd11e5d767 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp @@ -70,7 +70,7 @@ #endif uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { WRITE_PIN(mosi_pin, !!(b & 0x80)); WRITE_PIN(sck_pin, HIGH); @@ -80,16 +80,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(mosi_pin, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE_PIN(sck_pin, HIGH); b <<= 1; if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(sck_pin, LOW); } } @@ -99,7 +99,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { WRITE_PIN(sck_pin, LOW); @@ -108,13 +108,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck WRITE_PIN(sck_pin, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE_PIN(sck_pin, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(mosi_pin, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(sck_pin, HIGH); } b <<= 1; @@ -127,11 +127,11 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck static uint8_t SPI_speed = 0; static uint8_t swSpiInit(const uint8_t spi_speed, const uint8_t clk_pin, const uint8_t mosi_pin) { - return spi_speed; + return spi_speed; } static void u8g_sw_spi_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) + #if U8G_SPI_USE_MODE_3 swSpiTransfer_mode_3(val, SPI_speed, clockPin, -1, dataPin); #else swSpiTransfer_mode_0(val, SPI_speed, clockPin, -1, dataPin); @@ -159,15 +159,15 @@ uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt break; case U8G_COM_MSG_CHIP_SELECT: - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + #if U8G_SPI_USE_MODE_3 // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel(u8g, U8G_PI_CS, LOW); } else { u8g_SetPILevel(u8g, U8G_PI_CS, HIGH); - u8g_SetPILevel(u8g, U8G_PI_SCK, 0); // Set SCK to mode 0 idle state after CS goes inactive + u8g_SetPILevel(u8g, U8G_PI_SCK, 0); // Set SCK to mode 0 idle state after CS goes inactive } #else u8g_SetPILevel(u8g, U8G_PI_CS, !arg_val); diff --git a/Marlin/src/HAL/RP2040/HAL.cpp b/Marlin/src/HAL/RP2040/HAL.cpp new file mode 100644 index 0000000000..51f68648bc --- /dev/null +++ b/Marlin/src/HAL/RP2040/HAL.cpp @@ -0,0 +1,298 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "HAL.h" +//#include "usb_serial.h" + +#include "../../inc/MarlinConfig.h" +#include "../shared/Delay.h" +#include "../../module/temperature.h" // For OVERSAMPLENR + +extern "C" { + #include "pico/bootrom.h" + #include "hardware/watchdog.h" + #include "pico/multicore.h" + #include "hardware/adc.h" + #include "pico/time.h" +} + +#if HAS_SD_HOST_DRIVE + #include "msc_sd.h" +#endif + +// ------------------------ +// Public Variables +// ------------------------ + +volatile uint32_t adc_accumulators[5] = {0}; // Accumulators for oversampling (sum of readings) +volatile uint8_t adc_counts[5] = {0}; // Count of readings accumulated per channel +volatile uint16_t adc_values[5] = {4095, 4095, 4095, 4095, 4095}; // Averaged ADC values (single reading equivalent) - initialized to max (open circuit) + +// Core monitoring for watchdog +volatile uint32_t core0_last_heartbeat = 0; // Timestamp of Core 0's last activity +volatile uint32_t core1_last_heartbeat = 0; // Timestamp of Core 1's last activity +#if ENABLED(MARLIN_DEV_MODE) + volatile bool core1_freeze_test = false; // Flag to freeze Core 1 for watchdog testing +#endif +volatile uint8_t current_pin; +volatile bool MarlinHAL::adc_has_result; +volatile uint8_t adc_channels_enabled[5] = {false}; // Track which ADC channels are enabled + +// Core 1 ADC reading task - dynamically reads all enabled channels with oversampling +void core1_adc_task() { + static uint32_t last_temp_update = 0; + + while (true) { + #if ENABLED(MARLIN_DEV_MODE) + // Check if we should freeze for watchdog test + if (core1_freeze_test) { + // Stop updating heartbeat and spin forever + while (core1_freeze_test) { + busy_wait_us(100000); // 100ms delay + } + } + #endif + + // Scan all enabled ADC channels + for (uint8_t channel = 0; channel < 5; channel++) { + if (!adc_channels_enabled[channel]) continue; + + // Enable temperature sensor if reading channel 4 + if (channel == 4) { + adc_set_temp_sensor_enabled(true); + } + + // Select and read the channel + adc_select_input(channel); + busy_wait_us(100); // Settling delay + adc_fifo_drain(); + adc_run(true); + + // Wait for conversion with timeout + uint32_t timeout = 10000; + while (adc_fifo_is_empty() && timeout--) { + busy_wait_us(1); + } + + adc_run(false); + uint16_t reading = adc_fifo_is_empty() ? 0 : adc_fifo_get(); + + // Accumulate readings for oversampling + adc_accumulators[channel] += reading; + adc_counts[channel]++; + + // When we reach the full oversampling count, calculate averaged value (Marlin ISR does its own oversampling) + if (adc_counts[channel] >= OVERSAMPLENR) { + adc_values[channel] = adc_accumulators[channel] / OVERSAMPLENR; // Return single-reading equivalent + adc_accumulators[channel] = 0; + adc_counts[channel] = 0; + } + + // Disable temp sensor after reading to save power + if (channel == 4) { + adc_set_temp_sensor_enabled(false); + } + } + + // Core 1 just provides ADC readings - don't trigger temperature updates from here + // Let Marlin's main temperature ISR on Core 0 handle the timing and updates + uint32_t now = time_us_32(); + if (now - last_temp_update >= 100000) { // 100ms = 100000 microseconds + last_temp_update = now; + #if ENABLED(USE_WATCHDOG) + // Refresh watchdog here like AVR ISR does indirectly via temperature updates + // Use 2 second delay to allow watchdog_init to be called during boot + static uint32_t core1_start_time = 0; + if (core1_start_time == 0) core1_start_time = time_us_32(); + + if (time_us_32() - core1_start_time > 2000000) { + hal.watchdog_refresh(1); // Refresh from Core 1 + } + #endif + } + + // Delay between full scan cycles + busy_wait_us(10000); // 10ms between scans + } +} + +volatile uint16_t adc_result; + +// ------------------------ +// Public functions +// ------------------------ + +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); + +// HAL initialization task +void MarlinHAL::init() { + // Ensure F_CPU is a constant expression. + // If the compiler breaks here, it means that delay code that should compute at compile time will not work. + // So better safe than sorry here. + constexpr unsigned int cpuFreq = F_CPU; + UNUSED(cpuFreq); + + #if HAS_MEDIA && DISABLED(ONBOARD_SDIO) && PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); // Try to set SD_SS_PIN inactive before any other SPI users start up + #endif + + #if PIN_EXISTS(LED) + OUT_WRITE(LED_PIN, LOW); + #endif + + #if ENABLED(SRAM_EEPROM_EMULATION) + // __HAL_RCC_PWR_CLK_ENABLE(); + // HAL_PWR_EnableBkUpAccess(); // Enable access to backup SRAM + // __HAL_RCC_BKPSRAM_CLK_ENABLE(); + // LL_PWR_EnableBkUpRegulator(); // Enable backup regulator + // while (!LL_PWR_IsActiveFlag_BRR()); // Wait until backup regulator is initialized + #endif + + HAL_timer_init(); + + #if ALL(EMERGENCY_PARSER, USBD_USE_CDC) + USB_Hook_init(); + #endif + + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler + + TERN_(HAS_SD_HOST_DRIVE, MSC_SD_init()); // Enable USB SD card access + + #if PIN_EXISTS(USB_CONNECT) + OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection + delay_ms(1000); // Give OS time to notice + WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); + #endif +} + +uint8_t MarlinHAL::get_reset_source() { + return watchdog_enable_caused_reboot() ? RST_WATCHDOG : 0; +} + +void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); } + +// ------------------------ +// Watchdog Timer +// ------------------------ + +#if ENABLED(USE_WATCHDOG) + + #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout + + extern "C" { + #include "hardware/watchdog.h" + } + + void MarlinHAL::watchdog_init() { + #if DISABLED(DISABLE_WATCHDOG_INIT) + static_assert(WDT_TIMEOUT_US > 1000, "WDT Timeout is too small, aborting"); + // Initialize Core 0 heartbeat + core0_last_heartbeat = time_us_32(); + watchdog_enable(WDT_TIMEOUT_US/1000, true); + #endif + } + + void MarlinHAL::watchdog_refresh(const uint8_t core/*=0*/) { + if (core == 0) { + // Update Core 0 heartbeat + core0_last_heartbeat = time_us_32(); + + // Check if Core 1 is alive (2 second timeout) + if (time_us_32() - core1_last_heartbeat < 2000000) { + watchdog_update(); // Only refresh if Core 1 is responding + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + TOGGLE(LED_PIN); // Heartbeat indicator + #endif + } + // If Core 1 is stuck, don't refresh - let watchdog reset the system + } + else { + // Update Core 1 heartbeat + core1_last_heartbeat = time_us_32(); + + // Check if Core 0 is alive (2 second timeout) + if (time_us_32() - core0_last_heartbeat < 2000000) { + watchdog_update(); // Only refresh if Core 0 is responding + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + TOGGLE(LED_PIN); // Heartbeat indicator + #endif + } + // If Core 0 is stuck, don't refresh - let watchdog reset the system + } + } + +#endif // USE_WATCHDOG + +// ------------------------ +// ADC +// ------------------------ + +void MarlinHAL::adc_init() { + analogReadResolution(HAL_ADC_RESOLUTION); + ::adc_init(); + adc_fifo_setup(true, false, 1, false, false); + // Launch Core 1 for continuous ADC reading + multicore_launch_core1(core1_adc_task); + adc_has_result = true; // Results are always available with continuous sampling +} + +void MarlinHAL::adc_enable(const pin_t pin) { + if (pin >= A0 && pin <= A3) { + adc_gpio_init(pin); + adc_channels_enabled[pin - A0] = true; // Mark this channel as enabled + } + else if (pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) { + adc_channels_enabled[4] = true; // Mark MCU temp channel as enabled + } +} + +void MarlinHAL::adc_start(const pin_t pin) { + // Just store which pin we need to read - values are continuously updated by Core 1 + current_pin = pin; +} + +uint16_t MarlinHAL::adc_value() { + // Return the latest ADC value from Core 1's continuous readings + const uint8_t channel = (current_pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) ? 4 : (current_pin - A0); + return adc_values[channel]; +} + +// Reset the system to initiate a firmware flash +void flashFirmware(const int16_t) { hal.reboot(); } + +extern "C" { + void * _sbrk(int incr); + extern unsigned int __StackLimit; // Lowest address the stack can grow to +} + +// Return free memory between end of heap and start of stack +int freeMemory() { + void* heap_end = _sbrk(0); + // Use the linker-provided stack limit instead of a local variable + // __StackLimit is the lowest address the stack can grow to + return (char*)&__StackLimit - (char*)heap_end; +} + +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/HAL.h b/Marlin/src/HAL/RP2040/HAL.h new file mode 100644 index 0000000000..a49b343899 --- /dev/null +++ b/Marlin/src/HAL/RP2040/HAL.h @@ -0,0 +1,215 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define CPU_32_BIT + +#ifndef F_CPU + #define F_CPU (XOSC_MHZ * 1000000UL) +#endif + +#include "arduino_extras.h" +#include "../../core/macros.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" +#include "watchdog.h" + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_SD_HOST_DRIVE + #include "msc_sd.h" +#endif + +// ADC index 4 is the MCU temperature +#define HAL_ADC_MCU_TEMP_DUMMY_PIN 127 +#define TEMP_SOC_PIN HAL_ADC_MCU_TEMP_DUMMY_PIN // ADC4 is internal temp sensor +#include "temp_soc.h" + +// +// Serial Ports +// + +#include "MarlinSerial.h" + +#if !WITHIN(SERIAL_PORT, -1, 1) + #error "SERIAL_PORT must be from -1 to 1." +#endif + +#ifdef SERIAL_PORT_2 + #if !WITHIN(SERIAL_PORT_2, -1, 1) + #error "SERIAL_PORT_2 must be from -1 to 1." + #endif +#endif + +#ifdef SERIAL_PORT_3 + #if !WITHIN(SERIAL_PORT_3, -1, 1) + #error "SERIAL_PORT_3 must be from -1 to 1." + #endif +#endif + +#ifdef LCD_SERIAL_PORT + #if !WITHIN(LCD_SERIAL_PORT, -1, 1) + #error "LCD_SERIAL_PORT must be from -1 to 1." + #endif +#endif + +// ------------------------ +// Defines +// ------------------------ + +/** + * TODO: review this to return 1 for pins that are not analog input + */ +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) (p) +#endif + +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define cli() __disable_irq() +#define sei() __enable_irq() + +// ------------------------ +// Types +// ------------------------ + +template struct IFPIN { typedef R type; }; +template struct IFPIN { typedef L type; }; +typedef IFPIN::type pin_t; + +class libServo; +typedef libServo hal_servo_t; +#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() +#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() + +// ------------------------ +// ADC +// ------------------------ + +#define HAL_ADC_VREF 3.3 +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif + +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif +void flashFirmware(const int16_t); + +// Maple Compatibility +typedef void (*systickCallback_t)(void); +void systick_attach_callback(systickCallback_t cb); +void HAL_SYSTICK_Callback(); + +extern volatile uint32_t systick_uptime_millis; + +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment +#define PWM_FREQUENCY 1000 // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency() + +// ------------------------ +// Class Utilities +// ------------------------ + +int freeMemory(); + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + // Watchdog + static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh(const uint8_t=0) 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 + + // Interrupts + static bool isr_state() { return !__get_PRIMASK(); } + static void isr_on() { __enable_irq(); } + static void isr_off() { __disable_irq(); } + + static void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from marlin.idle() + static void idletask() { TERN_(HAS_SD_HOST_DRIVE, tuh_task()); } + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source() {} + + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given pin. Called from Temperature::isr! + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static volatile bool adc_has_result; + static bool adc_ready() { return adc_has_result; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + + /** + * Set the frequency of the timer for the given pin as close as + * possible to the provided desired frequency. Internally calculate + * the required waveform generation mode, prescaler, and resolution + * values and set timer registers accordingly. + * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) + * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST_PWM_FAN Settings) + */ + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); +}; diff --git a/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp b/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp new file mode 100644 index 0000000000..dc332053bc --- /dev/null +++ b/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp @@ -0,0 +1,68 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(POSTMORTEM_DEBUGGING) + +#include "../shared/HAL_MinSerial.h" + +static void TXBegin() { + #if !WITHIN(SERIAL_PORT, -1, 2) + #warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error." + #warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port." + #else + #if SERIAL_PORT == -1 + USBSerial.begin(BAUDRATE); + #elif SERIAL_PORT == 0 + USBSerial.begin(BAUDRATE); + #elif SERIAL_PORT == 1 + Serial1.begin(BAUDRATE); + #endif + #endif +} + +static void TX(char b) { + #if SERIAL_PORT == -1 + USBSerial + #elif SERIAL_PORT == 0 + USBSerial + #elif SERIAL_PORT == 1 + Serial1 + #endif + .write(b); +} + +// A SW memory barrier, to ensure GCC does not overoptimize loops +#define sw_barrier() __asm__ volatile("": : :"memory"); + + +void install_min_serial() { + HAL_min_serial_init = &TXBegin; + HAL_min_serial_out = &TX; +} + +#endif // POSTMORTEM_DEBUGGING +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/HAL_SPI.cpp b/Marlin/src/HAL/RP2040/HAL_SPI.cpp new file mode 100644 index 0000000000..c88b6d1e5b --- /dev/null +++ b/Marlin/src/HAL/RP2040/HAL_SPI.cpp @@ -0,0 +1,228 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../inc/MarlinConfig.h" + +#include + +// ------------------------ +// Public Variables +// ------------------------ + +static SPISettings spiConfig; + +// ------------------------ +// Public functions +// ------------------------ + +#if ENABLED(SOFTWARE_SPI) + + // ------------------------ + // Software SPI + // ------------------------ + + #include "../shared/Delay.h" + + void spiBegin(void) { + OUT_WRITE(SD_SS_PIN, HIGH); + OUT_WRITE(SD_SCK_PIN, HIGH); + SET_INPUT(SD_MISO_PIN); + OUT_WRITE(SD_MOSI_PIN, HIGH); + } + + // Use function with compile-time value so we can actually reach the desired frequency + // Need to adjust this a little bit: on a 72MHz clock, we have 14ns/clock + // and we'll use ~3 cycles to jump to the method and going back, so it'll take ~40ns from the given clock here + #define CALLING_COST_NS (3U * 1000000000U) / (F_CPU) + void (*delaySPIFunc)(); + void delaySPI_125() { DELAY_NS(125 - CALLING_COST_NS); } + void delaySPI_250() { DELAY_NS(250 - CALLING_COST_NS); } + void delaySPI_500() { DELAY_NS(500 - CALLING_COST_NS); } + void delaySPI_1000() { DELAY_NS(1000 - CALLING_COST_NS); } + void delaySPI_2000() { DELAY_NS(2000 - CALLING_COST_NS); } + void delaySPI_4000() { DELAY_NS(4000 - CALLING_COST_NS); } + + void spiInit(uint8_t spiRate) { + // Use datarates Marlin uses + switch (spiRate) { + case SPI_FULL_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 8,000,000 actual: ~1.1M + case SPI_HALF_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 4,000,000 actual: ~1.1M + case SPI_QUARTER_SPEED:delaySPIFunc = &delaySPI_250; break; // desired: 2,000,000 actual: ~890K + case SPI_EIGHTH_SPEED: delaySPIFunc = &delaySPI_500; break; // desired: 1,000,000 actual: ~590K + case SPI_SPEED_5: delaySPIFunc = &delaySPI_1000; break; // desired: 500,000 actual: ~360K + case SPI_SPEED_6: delaySPIFunc = &delaySPI_2000; break; // desired: 250,000 actual: ~210K + default: delaySPIFunc = &delaySPI_4000; break; // desired: 125,000 actual: ~123K + } + SPI.begin(); + } + + // Begin SPI transaction, set clock, bit order, data mode + void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ } + + uint8_t HAL_SPI_RP2040_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3 + for (uint8_t bits = 8; bits--;) { + WRITE(SD_SCK_PIN, LOW); + WRITE(SD_MOSI_PIN, b & 0x80); + + delaySPIFunc(); + WRITE(SD_SCK_PIN, HIGH); + delaySPIFunc(); + + b <<= 1; // little setup time + b |= (READ(SD_MISO_PIN) != 0); + } + DELAY_NS(125); + return b; + } + + // Soft SPI receive byte + uint8_t spiRec() { + hal.isr_off(); // No interrupts during byte receive + const uint8_t data = HAL_SPI_RP2040_SpiTransfer_Mode_3(0xFF); + hal.isr_on(); // Enable interrupts + return data; + } + + // Soft SPI read data + void spiRead(uint8_t *buf, uint16_t nbyte) { + for (uint16_t i = 0; i < nbyte; i++) + buf[i] = spiRec(); + } + + // Soft SPI send byte + void spiSend(uint8_t data) { + hal.isr_off(); // No interrupts during byte send + HAL_SPI_RP2040_SpiTransfer_Mode_3(data); // Don't care what is received + hal.isr_on(); // Enable interrupts + } + + // Soft SPI send block + void spiSendBlock(uint8_t token, const uint8_t *buf) { + spiSend(token); + for (uint16_t i = 0; i < 512; i++) + spiSend(buf[i]); + } + +#else + + // ------------------------ + // Hardware SPI + // ------------------------ + + /** + * VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz + */ + + /** + * @brief Begin SPI port setup + * + * @return Nothing + * + * @details Only configures SS pin since stm32duino creates and initialize the SPI object + */ + void spiBegin() { + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + } + + // Configure SPI for specified SPI speed + void spiInit(uint8_t spiRate) { + // Use datarates Marlin uses + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 + case SPI_HALF_SPEED: clock = 5000000; break; + case SPI_QUARTER_SPEED: clock = 2500000; break; + case SPI_EIGHTH_SPEED: clock = 1250000; break; + case SPI_SPEED_5: clock = 625000; break; + case SPI_SPEED_6: clock = 300000; break; + default: + clock = 4000000; // Default from the SPI library + } + spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); + + //SPI.setMISO(SD_MISO_PIN); //todo: implement? bad interface + //SPI.setMOSI(SD_MOSI_PIN); + //SPI.setSCLK(SD_SCK_PIN); + + SPI.begin(); + } + + /** + * @brief Receives a single byte from the SPI port. + * + * @return Byte received + * + * @details + */ + uint8_t spiRec() { + uint8_t returnByte = SPI.transfer(0xFF); + return returnByte; + } + + /** + * @brief Receive a number of bytes from the SPI port to a buffer + * + * @param buf Pointer to starting address of buffer to write to. + * @param nbyte Number of bytes to receive. + * @return Nothing + * + * @details Uses DMA + */ + void spiRead(uint8_t *buf, uint16_t nbyte) { + if (nbyte == 0) return; + memset(buf, 0xFF, nbyte); + SPI.transfer(buf, nbyte); + } + + /** + * @brief Send a single byte on SPI port + * + * @param b Byte to send + * + * @details + */ + void spiSend(uint8_t b) { + SPI.transfer(b); + } + + /** + * @brief Write token and then write from 512 byte buffer to SPI (for SD card) + * + * @param buf Pointer with buffer start address + * @return Nothing + * + * @details Use DMA + */ + void spiSendBlock(uint8_t token, const uint8_t *buf) { + //uint8_t rxBuf[512]; + //SPI.transfer(token); + SPI.transfer((uint8_t*)buf, 512); //implement? bad interface + } + +#endif // SOFTWARE_SPI + +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/MarlinSerial.cpp b/Marlin/src/HAL/RP2040/MarlinSerial.cpp new file mode 100644 index 0000000000..5e3bf0c148 --- /dev/null +++ b/Marlin/src/HAL/RP2040/MarlinSerial.cpp @@ -0,0 +1,69 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../inc/MarlinConfig.h" +#include "MarlinSerial.h" + +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif + +#include + +// Marlin uses: -1=USB, 0=UART0, 1=UART1 +// Arduino uses: Serial=USB, Serial1=UART0, Serial2=UART1 +// +// To remap Arduino's numbering to Marlin's convention, we create MarlinSerial0/MarlinSerial1 +// as new UART instances with custom pins. +// +// We use distinct names (MarlinSerial0/MarlinSerial1) to avoid symbol conflicts with +// the Arduino framework's pre-defined Serial1/Serial2 objects, which use the same +// underlying hardware (_UART0_ and _UART1_). + +// Create Serial0 as UART0 with custom or default pins +arduino::UART MarlinSerial0( + #if PINS_EXIST(SERIAL0_TX, SERIAL0_RX) + SERIAL0_TX_PIN, SERIAL0_RX_PIN // Custom pins for UART0 (Marlin Serial0) + #else + 0, 1 // Default UART0 pins (GP0/GP1) + #endif +); + +// Not using PINS_EXIST(SERIAL1_TX, SERIAL1_RX) because SERIAL1_TX and SERIAL1_RX +// are defined in framework-arduino-mbed/variants/RASPBERRY_PI_PICO/pins_arduino.h + +// Create Serial1 as UART1 with custom or default pins +#if defined(SERIAL1_TX_PIN) && defined(SERIAL1_RX_PIN) + arduino::UART MarlinSerial1(SERIAL1_TX_PIN, SERIAL1_RX_PIN); // Custom pins for UART1 (Marlin Serial1) +#endif + +// Wrap the serial ports for Marlin +DefaultSerial0 MSerial0(false, MarlinSerial0); // Marlin Serial0 = UART0 +#if defined(SERIAL1_TX_PIN) && defined(SERIAL1_RX_PIN) + DefaultSerial1 MSerial1(false, MarlinSerial1); // Marlin Serial1 = UART1 +#endif +DefaultSerial2 MSerial2(false, Serial); // Marlin Serial2 = USB (-1) + +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/MarlinSerial.h b/Marlin/src/HAL/RP2040/MarlinSerial.h new file mode 100644 index 0000000000..f407a838df --- /dev/null +++ b/Marlin/src/HAL/RP2040/MarlinSerial.h @@ -0,0 +1,80 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif + +#include "../../core/serial_hook.h" + +/** + * Serial Port Configuration for RP2040 (Raspberry Pi Pico) + * + * Arduino-Pico Core Serial Objects: + * - Serial: USB Serial (CDC ACM) + * - Serial1: Hardware UART0 + * - Serial2: Hardware UART1 + * - SerialUSB: Alias for Serial (USB) + * + * Marlin Serial Wrappers: + * - MSerial0: Wrapper for MarlinSerial0 (UART0), used as Serial0 + * - MSerial1: Wrapper for MarlinSerial1 (UART1), declared dynamically if used + * - MSerial2: Wrapper for Serial (USB) + * - USBSerial: Wrapper for SerialUSB (USB) + * + * How it all joins together: + * - Configuration defines SERIAL_PORT, SERIAL_PORT_2, etc. (-1 to 1 range) + * - shared/serial_ports.h maps these to MYSERIAL1, MYSERIAL2, etc. + * - MYSERIAL1 uses MSerialX based on the port index + * - USB ports (-1) use USB_SERIAL_PORT (MSerial2) + */ + +// Forward declare our custom Serial objects (defined in MarlinSerial.cpp) +namespace arduino { class UART; } +extern arduino::UART MarlinSerial0; // Always declared +extern arduino::UART MarlinSerial1; // Custom Marlin Serial1 to avoid conflict + +typedef ForwardSerial1Class< decltype(MarlinSerial0) > DefaultSerial0; +extern DefaultSerial0 MSerial0; +typedef ForwardSerial1Class< decltype(MarlinSerial1) > DefaultSerial1; +extern DefaultSerial1 MSerial1; +typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial2; +extern DefaultSerial2 MSerial2; +typedef ForwardSerial1Class USBSerialType; +extern USBSerialType USBSerial; + +#define _DECLARE_SERIAL(X) \ + typedef ForwardSerial1Class DefaultSerial##X; \ + extern DefaultSerial##X MSerial##X +#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X) + +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 1 +#define USB_SERIAL_PORT(...) MSerial2 +#include "../shared/serial_ports.h" + +#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) + #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() +#endif diff --git a/Marlin/src/HAL/RP2040/README.md b/Marlin/src/HAL/RP2040/README.md new file mode 100644 index 0000000000..4f9f70b8c9 --- /dev/null +++ b/Marlin/src/HAL/RP2040/README.md @@ -0,0 +1 @@ +# RP2040 Hardware Interface diff --git a/Marlin/src/HAL/RP2040/Servo.cpp b/Marlin/src/HAL/RP2040/Servo.cpp new file mode 100644 index 0000000000..2b1b2a1744 --- /dev/null +++ b/Marlin/src/HAL/RP2040/Servo.cpp @@ -0,0 +1,93 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../inc/MarlinConfig.h" + +#if HAS_SERVOS + +#include "Servo.h" + +static uint_fast8_t servoCount = 0; +static libServo *servos[NUM_SERVOS] = {0}; +constexpr millis_t servoDelay[] = SERVO_DELAY; +static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); + +libServo::libServo() +: delay(servoDelay[servoCount]), + was_attached_before_pause(false), + value_before_pause(0) +{ + servos[servoCount++] = this; +} + +int8_t libServo::attach(const int pin) { + if (servoCount >= MAX_SERVOS) return -1; + if (pin > 0) servo_pin = pin; + auto result = pico_servo.attach(servo_pin); + return result; +} + +int8_t libServo::attach(const int pin, const int min, const int max) { + if (servoCount >= MAX_SERVOS) return -1; + if (pin > 0) servo_pin = pin; + auto result = pico_servo.attach(servo_pin, min, max); + return result; +} + +void libServo::move(const int value) { + if (attach(0) >= 0) { + pico_servo.write(value); + safe_delay(delay); + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); + } +} + +void libServo::pause() { + was_attached_before_pause = pico_servo.attached(); + if (was_attached_before_pause) { + value_before_pause = pico_servo.read(); + pico_servo.detach(); + } +} + +void libServo::resume() { + if (was_attached_before_pause) { + attach(); + move(value_before_pause); + } +} + +void libServo::pause_all_servos() { + for (auto& servo : servos) + if (servo) servo->pause(); +} + +void libServo::resume_all_servos() { + for (auto& servo : servos) + if (servo) servo->resume(); +} + +#endif // HAS_SERVOS +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/Servo.h b/Marlin/src/HAL/RP2040/Servo.h new file mode 100644 index 0000000000..031610fd1d --- /dev/null +++ b/Marlin/src/HAL/RP2040/Servo.h @@ -0,0 +1,77 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +#if 1 + +#include "../../core/millis_t.h" + +// Inherit and expand on the official library +class libServo { + public: + libServo(); + int8_t attach(const int pin = 0); // pin == 0 uses value from previous call + int8_t attach(const int pin, const int min, const int max); + void detach() { pico_servo.detach(); } + int read() { return pico_servo.read(); } + void move(const int value); + + void pause(); + void resume(); + + static void pause_all_servos(); + static void resume_all_servos(); + static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority); + + private: + Servo pico_servo; + + int servo_pin = 0; + millis_t delay = 0; + + bool was_attached_before_pause; + int value_before_pause; +}; + +#else + +class libServo: public Servo { + public: + void move(const int value) { + constexpr uint16_t servo_delay[] = SERVO_DELAY; + static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); + + if (attach(servo_info[servoIndex].Pin.nbr) >= 0) { // try to reattach + write(value); + safe_delay(servo_delay[servoIndex]); // delay to allow servo to reach position + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); + } + + } +}; + +class libServo; +typedef libServo hal_servo_t; + +#endif diff --git a/Marlin/src/HAL/RP2040/arduino_extras.cpp b/Marlin/src/HAL/RP2040/arduino_extras.cpp new file mode 100644 index 0000000000..cdc0a0abf2 --- /dev/null +++ b/Marlin/src/HAL/RP2040/arduino_extras.cpp @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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_RP2040__ + +#include + +char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s) { + char format_string[20]; + snprintf(format_string, 20, "%%%d.%df", __width, __prec); + sprintf(__s, format_string, __val); + return __s; +} + +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/arduino_extras.h b/Marlin/src/HAL/RP2040/arduino_extras.h new file mode 100644 index 0000000000..9794140212 --- /dev/null +++ b/Marlin/src/HAL/RP2040/arduino_extras.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// #include +// #include +// #include +// #include + +char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); diff --git a/Marlin/src/HAL/RP2040/docs/rp2040-datasheet.pdf b/Marlin/src/HAL/RP2040/docs/rp2040-datasheet.pdf new file mode 100644 index 0000000000..4c5c9db2e3 Binary files /dev/null and b/Marlin/src/HAL/RP2040/docs/rp2040-datasheet.pdf differ diff --git a/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp b/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp new file mode 100644 index 0000000000..bf52109173 --- /dev/null +++ b/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp @@ -0,0 +1,108 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(FLASH_EEPROM_EMULATION) + +#include "../../shared/eeprom_api.h" + +// NOTE: The Bigtreetech SKR Pico has an onboard W25Q16 flash module + +// RP2040 Flash-based EEPROM emulation using internal flash memory +#include +#include + +// Flash sector size is already defined in hardware/flash.h as FLASH_SECTOR_SIZE +// Place EEPROM emulation at the end of flash, before the filesystem +// This assumes 2MB flash, adjust if using different flash size +#define FLASH_TARGET_OFFSET (PICO_FLASH_SIZE_BYTES - FLASH_SECTOR_SIZE) + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif + +static uint8_t eeprom_buffer[MARLIN_EEPROM_SIZE]; +static bool eeprom_data_written = false; +static bool eeprom_initialized = false; +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_start() { + if (!eeprom_initialized) { + // Read from flash into buffer + const uint8_t *flash_data = (const uint8_t *)(XIP_BASE + FLASH_TARGET_OFFSET); + memcpy(eeprom_buffer, flash_data, MARLIN_EEPROM_SIZE); + eeprom_initialized = true; + } + return true; +} + +bool PersistentStore::access_finish() { + if (eeprom_data_written) { + TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); + + // Disable interrupts during flash write + const uint32_t intstate = save_and_disable_interrupts(); + + // Erase and program the sector + flash_range_erase(FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE); + flash_range_program(FLASH_TARGET_OFFSET, eeprom_buffer, MARLIN_EEPROM_SIZE); + + // Restore interrupts + restore_interrupts(intstate); + + TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); + eeprom_data_written = false; + } + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t v = *value; + if (pos < (int)MARLIN_EEPROM_SIZE && v != eeprom_buffer[pos]) { + eeprom_buffer[pos] = v; + eeprom_data_written = true; + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + const uint8_t c = (pos < (int)MARLIN_EEPROM_SIZE) ? eeprom_buffer[pos] : 0xFF; + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +#endif // FLASH_EEPROM_EMULATION +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/RP2040/eeprom/eeprom_wired.cpp similarity index 83% rename from Marlin/src/HAL/STM32/eeprom_wired.cpp rename to Marlin/src/HAL/RP2040/eeprom/eeprom_wired.cpp index cf0468151e..7a5ca86c4c 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/RP2040/eeprom/eeprom_wired.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,11 +19,11 @@ * along with this program. If not, see . * */ -#include "../platforms.h" +#include "../../platforms.h" -#ifdef HAL_STM32 +#ifdef __PLAT_RP2040__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if USE_WIRED_EEPROM @@ -33,8 +32,8 @@ * with simple implementations supplied by Marlin. */ -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(E2END + 1) @@ -77,4 +76,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t } #endif // USE_WIRED_EEPROM -#endif // HAL_STM32 +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/endstop_interrupts.h b/Marlin/src/HAL/RP2040/endstop_interrupts.h new file mode 100644 index 0000000000..af538406b8 --- /dev/null +++ b/Marlin/src/HAL/RP2040/endstop_interrupts.h @@ -0,0 +1,60 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../module/endstops.h" + +// One ISR for all EXT-Interrupts +void endstop_ISR() { endstops.update(); } + +void setup_endstop_interrupts() { + #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN_PIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); +} diff --git a/Marlin/src/HAL/RP2040/fast_pwm.cpp b/Marlin/src/HAL/RP2040/fast_pwm.cpp new file mode 100644 index 0000000000..1349a1d59e --- /dev/null +++ b/Marlin/src/HAL/RP2040/fast_pwm.cpp @@ -0,0 +1,43 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../inc/MarlinConfigPre.h" + +#include "HAL.h" +#include "pinDefinitions.h" + +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { + analogWrite(pin, v); +} + +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { + mbed::PwmOut* pwm = digitalPinToPwm(pin); + if (pwm != NULL) delete pwm; + pwm = new mbed::PwmOut(digitalPinToPinName(pin)); + digitalPinToPwm(pin) = pwm; + pwm->period_ms(1000 / f_desired); +} + +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/fastio.cpp b/Marlin/src/HAL/RP2040/fastio.cpp new file mode 100644 index 0000000000..fa77106cef --- /dev/null +++ b/Marlin/src/HAL/RP2040/fastio.cpp @@ -0,0 +1,32 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../inc/MarlinConfig.h" + +void FastIO_init() { + +} + +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/fastio.h b/Marlin/src/HAL/RP2040/fastio.h new file mode 100644 index 0000000000..e84d2e7778 --- /dev/null +++ b/Marlin/src/HAL/RP2040/fastio.h @@ -0,0 +1,87 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Fast I/O interfaces for RP2040 + * These use GPIO register access for fast port manipulation. + */ + +// ------------------------ +// Public Variables +// ------------------------ + + +// ------------------------ +// Public functions +// ------------------------ + +void FastIO_init(); // Must be called before using fast io macros +#define FASTIO_INIT() FastIO_init() + +// ------------------------ +// Defines +// ------------------------ + +#define _BV32(b) (1UL << (b)) + +#ifndef PWM + #define PWM OUTPUT +#endif + +#define _WRITE(IO, V) digitalWrite((IO), (V)) + +#define _READ(IO) digitalRead(IO) +#define _TOGGLE(IO) digitalWrite(IO, !digitalRead(IO)) + +#define _GET_MODE(IO) +#define _SET_MODE(IO,M) pinMode(IO, M) +#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) //!< Output Push Pull Mode & GPIO_NOPULL +#define _SET_OUTPUT_OD(IO) pinMode(IO, OUTPUT_OPEN_DRAIN) + +#define WRITE(IO,V) _WRITE(IO,V) +#define READ(IO) _READ(IO) +#define TOGGLE(IO) _TOGGLE(IO) + +#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) +#define OUT_WRITE_OD(IO,V) do{ _SET_OUTPUT_OD(IO); WRITE(IO,V); }while(0) + +#define SET_INPUT(IO) _SET_MODE(IO, INPUT) //!< Input Floating Mode +#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) //!< Input with Pull-up activation +#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) //!< Input with Pull-down activation +#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) +#define SET_PWM(IO) _SET_MODE(IO, PWM) + +#define IS_INPUT(IO) +#define IS_OUTPUT(IO) + +#define PWM_PIN(P) true //digitalPinHasPWM(P) +#define NO_COMPILE_TIME_PWM + +// digitalRead/Write wrappers +#define extDigitalRead(IO) digitalRead(IO) +#define extDigitalWrite(IO,V) digitalWrite(IO,V) + +#undef I2C_SDA +#define I2C_SDA_PIN PIN_WIRE_SDA +#undef I2C_SCL +#define I2C_SCL_PIN PIN_WIRE_SCL diff --git a/Marlin/src/HAL/RP2040/inc/Conditionals_LCD.h b/Marlin/src/HAL/RP2040/inc/Conditionals_LCD.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/RP2040/inc/Conditionals_LCD.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/RP2040/inc/Conditionals_adv.h b/Marlin/src/HAL/RP2040/inc/Conditionals_adv.h new file mode 100644 index 0000000000..b96b3baa64 --- /dev/null +++ b/Marlin/src/HAL/RP2040/inc/Conditionals_adv.h @@ -0,0 +1,35 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 HAS_MEDIA && DISABLED(NO_SD_HOST_DRIVE) + #define HAS_SD_HOST_DRIVE 1 +#endif + +// Fix F_CPU not being a compile-time constant in RP2040 framework +#ifdef BOARD_F_CPU + #undef F_CPU + #define F_CPU BOARD_F_CPU +#endif + +// The Sensitive Pins array is not optimizable +#define RUNTIME_ONLY_ANALOG_TO_DIGITAL diff --git a/Marlin/src/HAL/RP2040/inc/Conditionals_post.h b/Marlin/src/HAL/RP2040/inc/Conditionals_post.h new file mode 100644 index 0000000000..ef7853b987 --- /dev/null +++ b/Marlin/src/HAL/RP2040/inc/Conditionals_post.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 no real or emulated EEPROM selected, fall back to SD emulation +#if USE_FALLBACK_EEPROM + #define SDCARD_EEPROM_EMULATION +#elif ANY(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 +#endif diff --git a/Marlin/src/HAL/RP2040/inc/Conditionals_type.h b/Marlin/src/HAL/RP2040/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/RP2040/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/RP2040/inc/SanityCheck.h b/Marlin/src/HAL/RP2040/inc/SanityCheck.h new file mode 100644 index 0000000000..e4b1d7ee8d --- /dev/null +++ b/Marlin/src/HAL/RP2040/inc/SanityCheck.h @@ -0,0 +1,60 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Test RP2040-specific configuration values for errors at compile-time. + */ +//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11) +// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" +//#endif + +#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA + #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise + #if USE_FALLBACK_EEPROM + #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." + #endif + #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." +#endif + +#if ENABLED(SRAM_EEPROM_EMULATION) + #error "SRAM_EEPROM_EMULATION is not supported for RP2040." +#endif + +#if ALL(PRINTCOUNTER, FLASH_EEPROM_EMULATION) + #warning "FLASH_EEPROM_EMULATION may cause long delays when writing and should not be used while printing." + #error "Disable PRINTCOUNTER or choose another EEPROM emulation." +#endif + +#if ENABLED(FLASH_EEPROM_LEVELING) + #error "FLASH_EEPROM_LEVELING is not supported for RP2040." +#endif + +#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on RP2040." +#elif ENABLED(SERIAL_STATS_DROPPED_RX) + #error "SERIAL_STATS_DROPPED_RX is not supported on RP2040." +#endif + +#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) + #error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are not supported for RP2040." +#endif diff --git a/Marlin/src/HAL/RP2040/msc_sd.cpp b/Marlin/src/HAL/RP2040/msc_sd.cpp new file mode 100644 index 0000000000..b0de2241e5 --- /dev/null +++ b/Marlin/src/HAL/RP2040/msc_sd.cpp @@ -0,0 +1,104 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_SD_HOST_DRIVE + +#include "../../sd/cardreader.h" + +#include // TinyUSB device stack + +#define BLOCK_SIZE 512 +#define SD_MULTIBLOCK_RETRY_CNT 1 + +DiskIODriver* diskIODriver() { + #if HAS_MULTI_VOLUME + #if SHARED_VOLUME_IS(SD_ONBOARD) + return &card.media_driver_sdcard; + #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE) + return &card.media_driver_usbFlash; + #endif + #else + return card.diskIODriver(); + #endif +} + +/** Callbacks used by TinyUSB MSC **/ + +extern "C" { + +bool tud_msc_ready_cb(uint8_t lun) { + return diskIODriver()->isReady(); +} + +int32_t tud_msc_read10_cb(uint8_t lun, uint32_t lba, void* buffer, uint32_t bufsize) { + const uint32_t blocks = bufsize / BLOCK_SIZE; + for (uint16_t rcount = SD_MULTIBLOCK_RETRY_CNT; rcount--; ) { + if (diskIODriver()->readBlocks(lba, (uint8_t*)buffer, blocks)) + return bufsize; // Success + } + return -1; // Failure after retries +} + +int32_t tud_msc_write10_cb(uint8_t lun, uint32_t lba, uint8_t const* buffer, uint32_t bufsize) { + const uint32_t blocks = bufsize / BLOCK_SIZE; + for (uint16_t rcount = SD_MULTIBLOCK_RETRY_CNT; rcount--; ) { + if (diskIODriver()->writeBlocks(lba, buffer, blocks)) + return bufsize; // Success + } + return -1; // Failure after retries +} + +void tud_msc_inquiry_cb(uint8_t lun, uint8_t vendor_id[8], uint8_t product_id[16], uint8_t product_rev[4]) { + memcpy(vendor_id, "MARLIN ", 8); + memcpy(product_id, "Product ", 16); + memcpy(product_rev, "0.01", 4); +} + +void tud_msc_capacity_cb(uint8_t lun, uint32_t* block_count, uint16_t* block_size) { + *block_count = diskIODriver()->cardSize(); + *block_size = BLOCK_SIZE; +} + +void tud_msc_start_stop_cb(uint8_t lun, uint8_t power_condition, bool start, bool load_eject) { + if (load_eject) { + if (start) { + // Handle media load + } else { + // Handle media eject + } + } +} + +} // extern "C" + +void MSC_SD_init() { + tusb_init(); + // Add USB reinitialization logic if needed +} + +#endif // HAS_SD_HOST_DRIVE +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/msc_sd.h b/Marlin/src/HAL/RP2040/msc_sd.h new file mode 100644 index 0000000000..1c13f5578d --- /dev/null +++ b/Marlin/src/HAL/RP2040/msc_sd.h @@ -0,0 +1,24 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 MSC_SD_init(); diff --git a/Marlin/src/HAL/RP2040/pinsDebug.h b/Marlin/src/HAL/RP2040/pinsDebug.h new file mode 100644 index 0000000000..8f58089fb1 --- /dev/null +++ b/Marlin/src/HAL/RP2040/pinsDebug.h @@ -0,0 +1,167 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include +#include "HAL.h" + +#ifndef NUM_DIGITAL_PINS + #error "Expected NUM_DIGITAL_PINS not found." +#endif + +/** + * Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order) + * because the variants in this platform do not always define all the I/O port/pins + * that a CPU has. + * + * VARIABLES: + * Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and + * digitalWrite commands and by M42. + * - does not contain port/pin info + * - is not in port/pin order + * - typically a variant will only assign Ard_num to port/pins that are actually used + * Index - M43 counter - only used to get Ard_num + * x - a parameter/argument used to search the pin_array to try to find a signal name + * associated with a Ard_num + * Port_pin - port number and pin number for use with CPU registers and printing reports + * + * Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num + * are accessed and/or displayed. + * + * Three arrays are used. + * + * digitalPin[] is provided by the platform. It consists of the Port_pin numbers in + * Arduino pin number order. + * + * pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by + * the preprocessor. Only the signals associated with enabled options are in this table. + * It contains: + * - name of the signal + * - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines. + * EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the + * argument to digitalPinToPinName(IO) to get the Port_pin number + * - if it is a digital or analog signal. PWMs are considered digital here. + * + * pin_xref is a structure generated by this header file. It is generated by the + * preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the + * platform for this variant. + * - Ard_num + * - printable version of Port_pin + * + * Routines with an "x" as a parameter/argument are used to search the pin_array to try to + * find a signal name associated with a port/pin. + * + * NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that + * signal. The Arduino pin number is listed by the M43 I command. + */ + +/** + * Pins Debugging for RP2040 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS +#define NUM_ANALOG_FIRST A0 + +#define MODE_PIN_INPUT 0 // Input mode (reset state) +#define MODE_PIN_OUTPUT 1 // General purpose output mode +#define MODE_PIN_ALT 2 // Alternate function mode +#define MODE_PIN_ANALOG 3 // Analog mode + +#define getPinByIndex(x) pin_array[x].pin +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define digitalPinToAnalogIndex(P) digital_pin_to_analog_pin(P) + +uint8_t get_pin_mode(const pin_t pin) { + // Check if pin is in alternate function mode (I2C, SPI, etc.) + const uint32_t gpio_func = gpio_get_function(pin); + + // GPIO_FUNC_I2C is typically function 3 on RP2040 + if ( gpio_func == GPIO_FUNC_I2C + || gpio_func == GPIO_FUNC_SPI + || gpio_func == GPIO_FUNC_UART + || gpio_func == GPIO_FUNC_PWM + ) { + return MODE_PIN_ALT; + } + + // For GPIO mode, check direction + return gpio_get_dir(pin) ? MODE_PIN_OUTPUT : MODE_PIN_INPUT; +} + +bool getValidPinMode(const pin_t pin) { + const uint8_t pin_mode = get_pin_mode(pin); + return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM +} + +#define isValidPin(P) WITHIN(P, 0, pin_t(NUMBER_PINS_TOTAL - 1)) + +int8_t digital_pin_to_analog_pin(pin_t pin) { + pin -= NUM_ANALOG_FIRST; + return (WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) ? pin : -1; +} + +bool isAnalogPin(const pin_t pin) { + return digital_pin_to_analog_pin(pin) != -1; +} + +#define digitalRead_mod(A) extDigitalRead(A) // must use Arduino pin numbers when doing reads +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin + +//bool is_digital(const pin_t pin) { +// const uint8_t pin_mode = get_pin_mode(pin); +// return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; +//} + +bool pwm_status(const pin_t pin) { + // Check if this pin is configured for PWM + return PWM_PIN(pin) && get_pin_mode(pin) == MODE_PIN_ALT; +} + +void printPinPWM(const pin_t pin) { + if (pwm_status(pin)) { + // RP2040 has hardware PWM on specific pins + char buffer[22]; + sprintf_P(buffer, PSTR("PWM: pin %d "), pin); + SERIAL_ECHO(buffer); + } +} + +void printPinPort(const pin_t pin) {} diff --git a/Marlin/src/HAL/RP2040/spi_pins.h b/Marlin/src/HAL/RP2040/spi_pins.h new file mode 100644 index 0000000000..e6ee840b55 --- /dev/null +++ b/Marlin/src/HAL/RP2040/spi_pins.h @@ -0,0 +1,38 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Define SPI Pins: SCK, MISO, MOSI, SS + */ +#ifndef SD_SCK_PIN + #define SD_SCK_PIN PIN_SPI_SCK +#endif +#ifndef SD_MISO_PIN + #define SD_MISO_PIN PIN_SPI_MISO +#endif +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN PIN_SPI_MOSI +#endif +#ifndef SD_SS_PIN + #define SD_SS_PIN PIN_SPI_SS +#endif diff --git a/Marlin/src/HAL/RP2040/temp_soc.h b/Marlin/src/HAL/RP2040/temp_soc.h new file mode 100644 index 0000000000..e182fb88dc --- /dev/null +++ b/Marlin/src/HAL/RP2040/temp_soc.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +// RP2040 internal temperature sensor +// Formula: T = 27 - (ADC_voltage - 0.706) / 0.001721 +// ADC_voltage = (RAW / OVERSAMPLENR) * 3.3 / 4096 (RAW is accumulated over OVERSAMPLENR samples) +// T = 27 - ((RAW / OVERSAMPLENR) * 3.3 / 4096 - 0.706) / 0.001721 +// Simplified: T = 437.423 - (RAW / OVERSAMPLENR) * 0.46875 + +#define TEMP_SOC_SENSOR(RAW) (437.423f - ((RAW) / OVERSAMPLENR) * 0.46875f) diff --git a/Marlin/src/HAL/RP2040/timers.cpp b/Marlin/src/HAL/RP2040/timers.cpp new file mode 100644 index 0000000000..88d5af2983 --- /dev/null +++ b/Marlin/src/HAL/RP2040/timers.cpp @@ -0,0 +1,126 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 __PLAT_RP2040__ + +#include "../../inc/MarlinConfig.h" + +alarm_pool_t* HAL_timer_pool_0; +alarm_pool_t* HAL_timer_pool_1; +alarm_pool_t* HAL_timer_pool_2; +alarm_pool_t* HAL_timer_pool_3; + +struct repeating_timer HAL_timer_0; +struct repeating_timer HAL_timer_1; +struct repeating_timer HAL_timer_2; +struct repeating_timer HAL_timer_3; + +volatile bool HAL_timer_irq_en[4] = { false, false, false, false }; + +void HAL_timer_init() { + //reserve all the available alarm pools to use as "pseudo" hardware timers + //HAL_timer_pool_0 = alarm_pool_create(0,2); + HAL_timer_pool_1 = alarm_pool_create(1, 6); + HAL_timer_pool_0 = HAL_timer_pool_1; + HAL_timer_pool_2 = alarm_pool_create(2, 6); + HAL_timer_pool_3 = HAL_timer_pool_2; + //HAL_timer_pool_3 = alarm_pool_create(3, 6); + + irq_set_priority(TIMER_IRQ_0, 0xC0); + irq_set_priority(TIMER_IRQ_1, 0x80); + irq_set_priority(TIMER_IRQ_2, 0x40); + irq_set_priority(TIMER_IRQ_3, 0x00); + + //alarm_pool_init_default(); +} + +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { + const int64_t freq = (int64_t)frequency, + us = (1000000ll / freq) * -1ll; + bool result; + switch (timer_num) { + case 0: + result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_0, us, HAL_timer_repeating_0_callback, NULL, &HAL_timer_0); + break; + case 1: + result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_1, us, HAL_timer_repeating_1_callback, NULL, &HAL_timer_1); + break; + case 2: + result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_2, us, HAL_timer_repeating_2_callback, NULL, &HAL_timer_2); + break; + case 3: + result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_3, us, HAL_timer_repeating_3_callback, NULL, &HAL_timer_3); + break; + } + UNUSED(result); +} + +void HAL_timer_stop(const uint8_t timer_num) { + switch (timer_num) { + case 0: cancel_repeating_timer(&HAL_timer_0); break; + case 1: cancel_repeating_timer(&HAL_timer_1); break; + case 2: cancel_repeating_timer(&HAL_timer_2); break; + case 3: cancel_repeating_timer(&HAL_timer_3); break; + } +} + +int64_t HAL_timer_alarm_pool_0_callback(long int, void*) { + if (HAL_timer_irq_en[0]) HAL_timer_0_callback(); + return 0; +} +int64_t HAL_timer_alarm_pool_1_callback(long int, void*) { + if (HAL_timer_irq_en[1]) HAL_timer_1_callback(); + return 0; +} +int64_t HAL_timer_alarm_pool_2_callback(long int, void*) { + if (HAL_timer_irq_en[2]) HAL_timer_2_callback(); + return 0; +} +int64_t HAL_timer_alarm_pool_3_callback(long int, void*) { + if (HAL_timer_irq_en[3]) HAL_timer_3_callback(); + return 0; +} + +bool HAL_timer_repeating_0_callback(repeating_timer* timer) { + if (HAL_timer_irq_en[0]) HAL_timer_0_callback(); + return true; +} +bool HAL_timer_repeating_1_callback(repeating_timer* timer) { + if (HAL_timer_irq_en[1]) HAL_timer_1_callback(); + return true; +} +bool HAL_timer_repeating_2_callback(repeating_timer* timer) { + if (HAL_timer_irq_en[2]) HAL_timer_2_callback(); + return true; +} +bool HAL_timer_repeating_3_callback(repeating_timer* timer) { + if (HAL_timer_irq_en[3]) HAL_timer_3_callback(); + return true; +} + +void __attribute__((weak)) HAL_timer_0_callback() {} +void __attribute__((weak)) HAL_timer_1_callback() {} +void __attribute__((weak)) HAL_timer_2_callback() {} +void __attribute__((weak)) HAL_timer_3_callback() {} + +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/timers.h b/Marlin/src/HAL/RP2040/timers.h new file mode 100644 index 0000000000..8d9fde57a8 --- /dev/null +++ b/Marlin/src/HAL/RP2040/timers.h @@ -0,0 +1,164 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +#include "../../core/macros.h" + +#ifdef PICO_TIME_DEFAULT_ALARM_POOL_DISABLED + #undef PICO_TIME_DEFAULT_ALARM_POOL_DISABLED + #define PICO_TIME_DEFAULT_ALARM_POOL_DISABLED 0 +#else + #define PICO_TIME_DEFAULT_ALARM_POOL_DISABLED 0 +#endif + +// ------------------------ +// Defines +// ------------------------ + +//#define _HAL_TIMER(T) _CAT(LPC_TIM, T) +//#define _HAL_TIMER_IRQ(T) TIMER##T##_IRQn +//#define __HAL_TIMER_ISR(T) extern "C" alarm_callback_t HAL_timer_alarm_pool_##T##_callback() +#define __HAL_TIMER_ISR(T) extern void HAL_timer_##T##_callback() +#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T) + +typedef uint64_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX) + +#define HAL_TIMER_RATE (1'000'000ULL) // fixed value as we use a microsecond timesource +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper +#endif +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP +#endif +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature +#endif +#ifndef MF_TIMER_PWM + #define MF_TIMER_PWM 3 // Timer Index for PWM +#endif + +#define TEMP_TIMER_RATE HAL_TIMER_RATE +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency + +#define STEPPER_TIMER_RATE HAL_TIMER_RATE / 10 // 100khz roughly +#define STEPPER_TIMER_TICKS_PER_US (0.1) // fixed value as we use a microsecond timesource +#define STEPPER_TIMER_PRESCALE (10) + +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE + +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) + +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) + +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_STEP) +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_TEMP) +#endif + +// Timer references by index +//#define STEP_TIMER_PTR _HAL_TIMER(MF_TIMER_STEP) +//#define TEMP_TIMER_PTR _HAL_TIMER(MF_TIMER_TEMP) + +extern alarm_pool_t *HAL_timer_pool_0; +extern alarm_pool_t *HAL_timer_pool_1; +extern alarm_pool_t *HAL_timer_pool_2; +extern alarm_pool_t *HAL_timer_pool_3; + +extern struct repeating_timer HAL_timer_0; + +void HAL_timer_0_callback(); +void HAL_timer_1_callback(); +void HAL_timer_2_callback(); +void HAL_timer_3_callback(); + +int64_t HAL_timer_alarm_pool_0_callback(long int, void*); +int64_t HAL_timer_alarm_pool_1_callback(long int, void*); +int64_t HAL_timer_alarm_pool_2_callback(long int, void*); +int64_t HAL_timer_alarm_pool_3_callback(long int, void*); + +bool HAL_timer_repeating_0_callback(repeating_timer* timer); +bool HAL_timer_repeating_1_callback(repeating_timer* timer); +bool HAL_timer_repeating_2_callback(repeating_timer* timer); +bool HAL_timer_repeating_3_callback(repeating_timer* timer); + +extern volatile bool HAL_timer_irq_en[4]; + +// ------------------------ +// Public functions +// ------------------------ + +void HAL_timer_init(); +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); +void HAL_timer_stop(const uint8_t timer_num); + +FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t compare) { + + if (timer_num == MF_TIMER_STEP && compare == HAL_TIMER_TYPE_MAX) { + HAL_timer_stop(timer_num); + return; + } + + compare *= 10; // Dirty fix, figure out a proper way + + switch (timer_num) { + case 0: + alarm_pool_add_alarm_in_us(HAL_timer_pool_0, compare, HAL_timer_alarm_pool_0_callback, 0, false); + break; + case 1: + alarm_pool_add_alarm_in_us(HAL_timer_pool_1, compare, HAL_timer_alarm_pool_1_callback, 0, false); + break; + case 2: + alarm_pool_add_alarm_in_us(HAL_timer_pool_2, compare, HAL_timer_alarm_pool_2_callback, 0, false); + break; + case 3: + alarm_pool_add_alarm_in_us(HAL_timer_pool_3, compare, HAL_timer_alarm_pool_3_callback, 0, false); + break; + } +} + +FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { + return 0; +} +FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { + if (timer_num == MF_TIMER_STEP) return 0ull; + return time_us_64(); +} + +FORCE_INLINE static void HAL_timer_enable_interrupt(const uint8_t timer_num) { + HAL_timer_irq_en[timer_num] = 1; +} +FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) { + HAL_timer_irq_en[timer_num] = 0; +} +FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { + return HAL_timer_irq_en[timer_num]; // Lucky coincidence that timer_num and rp2040 IRQ num matches +} + +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/RP2040/u8g/LCD_defines.h b/Marlin/src/HAL/RP2040/u8g/LCD_defines.h new file mode 100644 index 0000000000..acdd94b477 --- /dev/null +++ b/Marlin/src/HAL/RP2040/u8g/LCD_defines.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * RP2040 LCD-specific defines + */ +uint8_t u8g_com_rp2040_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // u8g_com_rp2040_ssd_i2c.cpp +#define U8G_COM_SSD_I2C_HAL u8g_com_rp2040_ssd_i2c_fn diff --git a/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp b/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp new file mode 100644 index 0000000000..ea42bf190d --- /dev/null +++ b/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp @@ -0,0 +1,108 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * 2-Wire I2C COM Driver + * + * Handles Hardware I2C on valid pin combinations. + * Wire library is used for Hardware I2C. + * + * Hardware I2C uses pins defined in pins_arduino.h. + */ + +#ifdef __PLAT_RP2040__ + +#include "../../../inc/MarlinConfig.h" + +#if HAS_U8GLIB_I2C_OLED + +#include + +#include +#ifndef MASTER_ADDRESS + #define MASTER_ADDRESS 0x01 +#endif + +/** + * BUFFER_LENGTH is defined in libraries\Wire\utility\WireBase.h + * Default value is 32 + * Increase this value to 144 to send U8G_COM_MSG_WRITE_SEQ in single block + */ +#ifndef BUFFER_LENGTH + #define BUFFER_LENGTH 32 +#endif +#if BUFFER_LENGTH > 144 + #error "BUFFER_LENGTH should not be greater than 144." +#endif +#define I2C_MAX_LENGTH (BUFFER_LENGTH - 1) + +uint8_t u8g_com_rp2040_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + + // Hardware I2C flag + //static bool i2c_initialized = false; // Flag to only run init/linking code once + //if (!i2c_initialized) { // Init runtime linkages + // i2c_initialized = true; // Only do this once + //} + + static uint8_t control; + // Use the global Wire instance (already initialized with correct pins for RP2040) + switch (msg) { + case U8G_COM_MSG_INIT: + Wire.setClock(400000); + // Wire already initialized in MarlinUI::init(), no need to call begin() again + break; + + case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1) + control = arg_val ? 0x40 : 0x00; + break; + + case U8G_COM_MSG_WRITE_BYTE: + ::Wire.beginTransmission(0x3C); + ::Wire.write(control); + ::Wire.write(arg_val); + ::Wire.endTransmission(); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t* dataptr = (uint8_t*)arg_ptr; + while (arg_val > 0) { + ::Wire.beginTransmission(0x3C); + ::Wire.write(control); + if (arg_val <= I2C_MAX_LENGTH) { + ::Wire.write(dataptr, arg_val); + arg_val = 0; + } + else { + ::Wire.write(dataptr, I2C_MAX_LENGTH); + arg_val -= I2C_MAX_LENGTH; + dataptr += I2C_MAX_LENGTH; + } + ::Wire.endTransmission(); + } + break; + } + } + return 1; +} + +#endif // HAS_U8GLIB_I2C_OLED +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/SAMD21/HAL.cpp b/Marlin/src/HAL/SAMD21/HAL.cpp new file mode 100644 index 0000000000..0a95366cc4 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/HAL.cpp @@ -0,0 +1,209 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#ifdef __SAMD21__ + +#include "../../inc/MarlinConfig.h" + +#include + +#if USING_HW_SERIALUSB + DefaultSerial1 MSerialUSB(false, SerialUSB); +#endif +#if USING_HW_SERIAL0 + DefaultSerial2 MSerial1(false, Serial1); +#endif +#if USING_HW_SERIAL1 + DefaultSerial3 MSerial2(false, Serial2); +#endif + +#define WDT_CONFIG_PER_7_Val 0x9u +#define WDT_CONFIG_PER_Pos 0 +#define WDT_CONFIG_PER_7 (WDT_CONFIG_PER_7_Val << WDT_CONFIG_PER_Pos) + +#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() { + // Set up the generic clock (GCLK2) used to clock the watchdog timer at 1.024kHz + GCLK->GENDIV.reg = GCLK_GENDIV_DIV(4) | // Divide the 32.768kHz clock source by divisor 32, where 2^(4 + 1): 32.768kHz/32=1.024kHz + GCLK_GENDIV_ID(2); // Select Generic Clock (GCLK) 2 + while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization + + REG_GCLK_GENCTRL = GCLK_GENCTRL_DIVSEL | // Set to divide by 2^(GCLK_GENDIV_DIV(4) + 1) + GCLK_GENCTRL_IDC | // Set the duty cycle to 50/50 HIGH/LOW + GCLK_GENCTRL_GENEN | // Enable GCLK2 + GCLK_GENCTRL_SRC_OSCULP32K | // Set the clock source to the ultra low power oscillator (OSCULP32K) + GCLK_GENCTRL_ID(2); // Select GCLK2 + while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization + + // Feed GCLK2 to WDT (Watchdog Timer) + REG_GCLK_CLKCTRL = GCLK_CLKCTRL_CLKEN | // Enable GCLK2 to the WDT + GCLK_CLKCTRL_GEN_GCLK2 | // Select GCLK2 + GCLK_CLKCTRL_ID_WDT; // Feed the GCLK2 to the WDT + while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization + + WDT->CONFIG.bit.PER = WDT_CONFIG_PER_7; // Set the WDT reset timeout to 4 seconds + while (WDT->STATUS.bit.SYNCBUSY); // Wait for synchronization + REG_WDT_CTRL = WDT_CTRL_ENABLE; // Enable the WDT in normal mode + while (WDT->STATUS.bit.SYNCBUSY); // Wait for synchronization + } + + // 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() { + WDT->CLEAR.reg = WDT_CLEAR_CLEAR_KEY; + while (WDT->STATUS.bit.SYNCBUSY); + } + +#endif + +// ------------------------ +// Types +// ------------------------ + +// ------------------------ +// Private Variables +// ------------------------ + +// ------------------------ +// Private functions +// ------------------------ + +void MarlinHAL::dma_init() {} + +// ------------------------ +// Public functions +// ------------------------ + +// HAL initialization task +void MarlinHAL::init() { + TERN_(DMA_IS_REQUIRED, dma_init()); + #if HAS_MEDIA + #if HAS_SD_DETECT && SD_CONNECTION_IS(ONBOARD) + SET_INPUT_PULLUP(SD_DETECT_PIN); + #endif + OUT_WRITE(SD_SS_PIN, HIGH); // Try to set SDSS inactive before any other SPI users start up + #endif +} + +#pragma push_macro("WDT") +#undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define +uint8_t MarlinHAL::get_reset_source() { + + return 0; +} +#pragma pop_macro("WDT") + +void MarlinHAL::reboot() { NVIC_SystemReset(); } + +extern "C" { + void * _sbrk(int incr); + extern unsigned int __bss_end__; // end of bss section +} + +// Return free memory between end of heap (or end bss) and whatever is current +int freeMemory() { + int free_memory, heap_end = (int)_sbrk(0); + return (int)&free_memory - (heap_end ?: (int)&__bss_end__); +} + +// ------------------------ +// ADC +// ------------------------ + +uint16_t MarlinHAL::adc_result; + +void MarlinHAL::adc_init() { + /* thanks to https://www.eevblog.com/forum/microcontrollers/samd21g18-adc-with-resrdy-interrupts-only-reads-once-or-twice/ */ + + ADC->CTRLA.bit.ENABLE = false; + while(ADC->STATUS.bit.SYNCBUSY); + + // load chip corrections + uint32_t bias = (*((uint32_t *) ADC_FUSES_BIASCAL_ADDR) & ADC_FUSES_BIASCAL_Msk) >> ADC_FUSES_BIASCAL_Pos; + uint32_t linearity = (*((uint32_t *) ADC_FUSES_LINEARITY_0_ADDR) & ADC_FUSES_LINEARITY_0_Msk) >> ADC_FUSES_LINEARITY_0_Pos; + linearity |= ((*((uint32_t *) ADC_FUSES_LINEARITY_1_ADDR) & ADC_FUSES_LINEARITY_1_Msk) >> ADC_FUSES_LINEARITY_1_Pos) << 5; + + /* Wait for bus synchronization. */ + while (ADC->STATUS.bit.SYNCBUSY) {}; + + ADC->CALIB.reg = ADC_CALIB_BIAS_CAL(bias) | ADC_CALIB_LINEARITY_CAL(linearity); + + /* Wait for bus synchronization. */ + while (ADC->STATUS.bit.SYNCBUSY) {}; + + ADC->CTRLA.bit.SWRST = true; + while(ADC->STATUS.bit.SYNCBUSY); + + ADC->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1; + ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_32| ADC_AVGCTRL_ADJRES(4);; + + ADC->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128 | + ADC_CTRLB_RESSEL_16BIT | + ADC_CTRLB_FREERUN; + while(ADC->STATUS.bit.SYNCBUSY); + + ADC->SAMPCTRL.bit.SAMPLEN = 0x00; + while(ADC->STATUS.bit.SYNCBUSY); + + ADC->INPUTCTRL.reg = ADC_INPUTCTRL_INPUTSCAN(HAL_ADC_AIN_LEN) // scan (INPUTSCAN + NUM_EXTUDERS - 1) pins + | ADC_INPUTCTRL_GAIN_DIV2 |ADC_INPUTCTRL_MUXNEG_GND| HAL_ADC_AIN_START ; /* set to first AIN */ + + while(ADC->STATUS.bit.SYNCBUSY); + + ADC->INTENSET.reg |= ADC_INTENSET_RESRDY; // enable Result Ready ADC interrupts + while (ADC->STATUS.bit.SYNCBUSY); + + NVIC_EnableIRQ(ADC_IRQn); // enable ADC interrupts + + NVIC_SetPriority(ADC_IRQn, 3); + + ADC->CTRLA.bit.ENABLE = true; +} + +volatile uint32_t adc_results[HAL_ADC_AIN_NUM_SENSORS]; + +void ADC_Handler() { + while(ADC->STATUS.bit.SYNCBUSY == 1); + int pos = ADC->INPUTCTRL.bit.INPUTOFFSET; + + adc_results[pos] = ADC->RESULT.reg; /* Read the value. */ + ADC->INTFLAG.reg = ADC_INTENSET_RESRDY; /* Clear the data ready flag. */ +} + +void MarlinHAL::adc_start(const pin_t pin) { + /* due to the way INPUTOFFSET works, the last sensor is the first position in the array + and we want the ADC_handler interrupt to be as simple possible, so we do the calculation here. + */ + unsigned int pos = PIN_TO_INPUTCTRL(pin) - HAL_ADC_AIN_START + 1; + if (pos == HAL_ADC_AIN_NUM_SENSORS) pos = 0; + adc_result = adc_results[pos]; // 16-bit resolution + //adc_result = 0xFFFF; +} + +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/HAL.h b/Marlin/src/HAL/SAMD21/HAL.h new file mode 100644 index 0000000000..5545630ce3 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/HAL.h @@ -0,0 +1,189 @@ +/** + * 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 + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +#define CPU_32_BIT + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" + +// ------------------------ +// Serial ports +// ------------------------ + +#include "../../core/serial_hook.h" +typedef ForwardSerial1Class< decltype(SerialUSB) > DefaultSerial1; +extern DefaultSerial1 MSerialUSB; + +typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; +typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; + +extern DefaultSerial2 MSerial0; +extern DefaultSerial3 MSerial1; + +#define __MSERIAL(X) MSerial##X +#define _MSERIAL(X) __MSERIAL(X) +#define MSERIAL(X) _MSERIAL(INCREMENT(X)) + +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 1 +#define USB_SERIAL_PORT(...) MSerialUSB +#include "../shared/serial_ports.h" + +typedef int8_t pin_t; + +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +class Servo; +typedef Servo hal_servo_t; + +// +// Interrupts +// +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() + +#define cli() __disable_irq() // Disable interrupts +#define sei() __enable_irq() // Enable interrupts + +// +// ADC +// + +#define HAL_ADC_FILTERED 1 // Disable Marlin's oversampling. The HAL filters ADC values. +#define HAL_ADC_VREF_MV 3300 +#define HAL_ADC_RESOLUTION 12 +#define HAL_ADC_AIN_START ADC_INPUTCTRL_MUXPOS_PIN3 +#define HAL_ADC_AIN_NUM_SENSORS 3 +#define HAL_ADC_AIN_LEN HAL_ADC_AIN_NUM_SENSORS-1 + +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + +// +// Tone +// +void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); +void noTone(const pin_t _pin); + +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +#ifdef __cplusplus + extern "C" { +#endif + +char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); + +extern "C" int freeMemory(); + +#ifdef __cplusplus + } +#endif + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + // 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 + + // Interrupts + static bool isr_state() { return !__get_PRIMASK(); } + static void isr_on() { sei(); } + static void isr_off() { cli(); } + + static void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from marlin.idle() + static void idletask() {} + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source() {} + + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch) {} + + // Begin ADC sampling on the given pin. Called from Temperature::isr! + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +private: + static void dma_init(); +}; diff --git a/Marlin/src/HAL/SAMD21/HAL_SPI.cpp b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp new file mode 100644 index 0000000000..d41f868cdb --- /dev/null +++ b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp @@ -0,0 +1,147 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +/** + * Hardware and software SPI implementations are included in this file. + * + * Control of the slave select pin(s) is handled by the calling routines and + * SAMD21 let hardware SPI handling to remove SS from its logic. + */ + +#ifdef __SAMD21__ + +// -------------------------------------------------------------------------- +// Includes +// -------------------------------------------------------------------------- + +#include "../../inc/MarlinConfig.h" +#include + +// -------------------------------------------------------------------------- +// Public functions +// -------------------------------------------------------------------------- + +#if ANY(SOFTWARE_SPI, FORCE_SOFT_SPI) + + // ------------------------ + // Software SPI + // ------------------------ + #error "Software SPI not supported for SAMD21. Use Hardware SPI." + +#else // !SOFTWARE_SPI + + static SPISettings spiConfig; + + // ------------------------ + // Hardware SPI + // ------------------------ + void spiBegin() { + spiInit(SPI_HALF_SPEED); + } + + void spiInit(uint8_t spiRate) { + // Use Marlin datarates + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 8000000; break; + case SPI_HALF_SPEED: clock = 4000000; break; + case SPI_QUARTER_SPEED: clock = 2000000; break; + case SPI_EIGHTH_SPEED: clock = 1000000; break; + case SPI_SIXTEENTH_SPEED: clock = 500000; break; + case SPI_SPEED_5: clock = 250000; break; + case SPI_SPEED_6: clock = 125000; break; + default: clock = 4000000; break; // Default from the SPI library + } + spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); + SPI.begin(); + } + + /** + * @brief Receives a single byte from the SPI port. + * + * @return Byte received + * + * @details + */ + uint8_t spiRec() { + SPI.beginTransaction(spiConfig); + uint8_t returnByte = SPI.transfer(0xFF); + SPI.endTransaction(); + return returnByte; + } + + /** + * @brief Receives a number of bytes from the SPI port to a buffer + * + * @param buf Pointer to starting address of buffer to write to. + * @param nbyte Number of bytes to receive. + * @return Nothing + */ + void spiRead(uint8_t *buf, uint16_t nbyte) { + if (nbyte == 0) return; + memset(buf, 0xFF, nbyte); + + SPI.beginTransaction(spiConfig); + SPI.transfer(buf, nbyte); + SPI.endTransaction(); + } + + /** + * @brief Sends a single byte on SPI port + * + * @param b Byte to send + * + * @details + */ + void spiSend(uint8_t b) { + SPI.beginTransaction(spiConfig); + SPI.transfer(b); + SPI.endTransaction(); + } + + /** + * @brief Write token and then write from 512 byte buffer to SPI (for SD card) + * + * @param buf Pointer with buffer start address + * @return Nothing + * + * @details Uses DMA + */ + void spiSendBlock(uint8_t token, const uint8_t *buf) { + SPI.beginTransaction(spiConfig); + SPI.transfer(token); + SPI.transfer((uint8_t*)buf, 512); + SPI.endTransaction(); + } + + void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { + spiConfig = SPISettings(spiClock, (BitOrder)bitOrder, dataMode); + SPI.beginTransaction(spiConfig); + } +#endif // !SOFTWARE_SPI + +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/MarlinSPI.h b/Marlin/src/HAL/SAMD21/MarlinSPI.h new file mode 100644 index 0000000000..7b5392793e --- /dev/null +++ b/Marlin/src/HAL/SAMD21/MarlinSPI.h @@ -0,0 +1,31 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#pragma once + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/SAMD21/SAMD21.h b/Marlin/src/HAL/SAMD21/SAMD21.h new file mode 100644 index 0000000000..b64c5ce725 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/SAMD21.h @@ -0,0 +1,64 @@ +/** + * 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 + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +#define SYNC(sc) while (sc) { \ + asm(""); \ + } + +// Get SAMD port/pin from specified arduino pin +#define GET_SAMD_PORT(P) _GET_SAMD_PORT(PIN_TO_SAMD_PIN(P)) +#define GET_SAMD_PIN(P) _GET_SAMD_PIN(PIN_TO_SAMD_PIN(P)) + +// Get external interrupt line associated to specified arduino pin +#define PIN_TO_EILINE(P) _SAMDPORTPIN_TO_EILINE(GET_SAMD_PORT(P), GET_SAMD_PIN(P)) + +// Get adc/ain associated to specified arduino pin +#define PIN_TO_ADC(P) (ANAPIN_TO_ADCAIN(P) >> 8) + +// Private defines +#define PIN_TO_SAMD_PIN(P) DIO##P##_PIN + +#define _GET_SAMD_PORT(P) ((P) >> 5) +#define _GET_SAMD_PIN(P) ((P) & 0x1F) + +// Get external interrupt line +#define _SAMDPORTPIN_TO_EILINE(P,B) ((P == 0 && WITHIN(B, 0, 31) && B != 26 && B != 28 && B != 29) ? (B) & 0xF \ + : (P == 1 && (WITHIN(B, 0, 25) || WITHIN(B, 30, 31))) ? (B) & 0xF \ + : (P == 1 && WITHIN(B, 26, 29)) ? 12 + (B) - 26 \ + : (P == 2 && (WITHIN(B, 0, 6) || WITHIN(B, 10, 31)) && B != 29) ? (B) & 0xF \ + : (P == 2 && B == 7) ? 9 \ + : (P == 3 && WITHIN(B, 0, 1)) ? (B) \ + : (P == 3 && WITHIN(B, 8, 12)) ? 3 + (B) - 8 \ + : (P == 3 && WITHIN(B, 20, 21)) ? 10 + (B) - 20 \ + : -1) + +#define A2_AIN 3 +#define A3_AIN 4 +#define A4_AIN 5 +#define PIN_TO_AIN(P) A##P##_AIN +#define AIN_TO_RESULT(P) ( (P - HAL_ADC_AIN_START == HAL_ADC_AIN_NUM_SENSORS-1) ? 0 : (P - HAL_ADC_AIN_START + 1) ) diff --git a/Marlin/src/HAL/SAMD21/Servo.cpp b/Marlin/src/HAL/SAMD21/Servo.cpp new file mode 100644 index 0000000000..704d0a2904 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/Servo.cpp @@ -0,0 +1,219 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +/** + * This comes from Arduino library which at the moment is buggy and uncompilable + */ + +#ifdef __SAMD21__ + +#include "../../inc/MarlinConfig.h" + +#if HAS_SERVOS + +#include "../shared/servo.h" +#include "../shared/servo_private.h" +#include "SAMD21.h" + +#define __TC_GCLK_ID(t) TC##t##_GCLK_ID +#define _TC_GCLK_ID(t) __TC_GCLK_ID(t) +#define TC_GCLK_ID _TC_GCLK_ID(SERVO_TC) + +#define _TC_PRESCALER(d) TC_CTRLA_PRESCALER_DIV##d##_Val +#define TC_PRESCALER(d) _TC_PRESCALER(d) + +#define __SERVO_IRQn(t) TC##t##_IRQn +#define _SERVO_IRQn(t) __SERVO_IRQn(t) +#define SERVO_IRQn _SERVO_IRQn(SERVO_TC) + +#define HAL_SERVO_TIMER_ISR() TC_HANDLER(SERVO_TC) + +#define TIMER_TCCHANNEL(t) ((t) & 1) +#define TC_COUNTER_START_VAL 0xFFFF + +static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval) + +FORCE_INLINE static uint16_t getTimerCount() { + Tcc * const tc = timer_config[SERVO_TC].pTcc; + + tc->CTRLBSET.reg = TCC_CTRLBCLR_CMD_READSYNC; + SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); + + return tc->COUNT.bit.COUNT; +} + +// ---------------------------- +// Interrupt handler for the TC +// ---------------------------- +HAL_SERVO_TIMER_ISR() { + Tcc * const tc = timer_config[SERVO_TC].pTcc; + const timer16_Sequence_t timer = + #ifndef _useTimer1 + _timer2 + #elif !defined(_useTimer2) + _timer1 + #else + (tc->INTFLAG.reg & tc->INTENSET.reg & TC_INTFLAG_MC0) ? _timer1 : _timer2 + #endif + ; + const uint8_t tcChannel = TIMER_TCCHANNEL(timer); + + 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 + // Clear the interrupt + tc->INTFLAG.reg = (tcChannel == 0) ? TC_INTFLAG_MC0 : TC_INTFLAG_MC1; + return; + } + #endif + tc->COUNT.reg = TC_COUNTER_START_VAL; // ...so reset the timer + SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); + } + else if (SERVO_INDEX(timer, cho) < ServoCount) // prior channel handled? + digitalWrite(SERVO(timer, cho).Pin.nbr, LOW); // pulse the prior channel LOW + + 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->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; // 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->CC[tcChannel].reg = min(cval, ival); + } + if (tcChannel == 0) { + SYNC(tc->SYNCBUSY.bit.CC0); + tc->INTFLAG.reg = TC_INTFLAG_MC0; // Clear the interrupt + } + else { + SYNC(tc->SYNCBUSY.bit.CC1); + tc->INTFLAG.reg = TC_INTFLAG_MC1; // Clear the interrupt + } +} + +void initISR(const timer16_Sequence_t timer) { + Tcc * const tc = timer_config[SERVO_TC].pTcc; + const uint8_t tcChannel = TIMER_TCCHANNEL(timer); + + static bool initialized = false; // Servo TC has been initialized + if (!initialized) { + NVIC_DisableIRQ(SERVO_IRQn); + + // Disable the timer + tc->CTRLA.bit.ENABLE = false; + SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); + + // Select GCLK0 as timer/counter input clock source + GCLK->CLKCTRL.reg =(GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(TCC0_GCLK_ID)); + SYNC (GCLK->STATUS.bit.SYNCBUSY); + + // Reset the timer + tc->CTRLA.bit.SWRST = true; + SYNC(tc->CTRLA.bit.SWRST); + + // Set timer counter mode to 16 bits + tc->CTRLA.reg = TC_CTRLA_MODE_COUNT16; + + // Set timer counter mode as normal PWM + tc->WAVE.bit.WAVEGEN = TCC_WAVE_WAVEGEN_NPWM_Val; + + // Set the prescaler factor + tc->CTRLA.bit.PRESCALER = TC_PRESCALER(SERVO_TIMER_PRESCALER); + + // Count down + tc->CTRLBSET.reg = TCC_CTRLBCLR_DIR; + SYNC(tc->SYNCBUSY.bit.CTRLB); + + // Reset all servo indexes + memset((void *)currentServoIndex, 0xFF, sizeof(currentServoIndex)); + + // Configure interrupt request + NVIC_ClearPendingIRQ(SERVO_IRQn); + NVIC_SetPriority(SERVO_IRQn, 5); + NVIC_EnableIRQ(SERVO_IRQn); + + initialized = true; + } + + if (!tc->CTRLA.bit.ENABLE) { + // Reset the timer counter + tc->COUNT.reg = TC_COUNTER_START_VAL; + SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); + + // Enable the timer and start it + tc->CTRLA.bit.ENABLE = true; + SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); + } + // First interrupt request after 1 ms + tc->CC[tcChannel].reg = getTimerCount() - (uint16_t)usToTicks(1000UL); + + if (tcChannel == 0 ) { + SYNC(tc->SYNCBUSY.bit.CC0); + + // Clear pending match interrupt + tc->INTFLAG.reg = TC_INTENSET_MC0; + // Enable the match channel interrupt request + tc->INTENSET.reg = TC_INTENSET_MC0; + } + else { + SYNC(tc->SYNCBUSY.bit.CC1); + + // Clear pending match interrupt + tc->INTFLAG.reg = TC_INTENSET_MC1; + // Enable the match channel interrupt request + tc->INTENSET.reg = TC_INTENSET_MC1; + } +} + +void finISR(const timer16_Sequence_t timer_index) { + Tcc * const tc = timer_config[SERVO_TC].pTcc; + const uint8_t tcChannel = TIMER_TCCHANNEL(timer_index); + + // Disable the match channel interrupt request + tc->INTENCLR.reg = (tcChannel == 0) ? TC_INTENCLR_MC0 : TC_INTENCLR_MC1; + + if (true + #if defined(_useTimer1) && defined(_useTimer2) + && (tc->INTENCLR.reg & (TC_INTENCLR_MC0|TC_INTENCLR_MC1)) == 0 + #endif + ) { + // Disable the timer if not used + tc->CTRLA.bit.ENABLE = false; + SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); + } +} + +#endif // HAS_SERVOS + +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/ServoTimers.h b/Marlin/src/HAL/SAMD21/ServoTimers.h new file mode 100644 index 0000000000..8980547683 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/ServoTimers.h @@ -0,0 +1,45 @@ +/** + * 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 + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +#define _useTimer1 +#define _useTimer2 + +#define TRIM_DURATION 5 // compensation ticks to trim adjust for digitalWrite delays +#define SERVO_TIMER_PRESCALER 64 // timer prescaler factor to 64 (avoid overflowing 16-bit clock counter, at 120MHz this is 1831 ticks per millisecond + +#define SERVO_TC 3 + +typedef enum { + #ifdef _useTimer1 + _timer1, + #endif + #ifdef _useTimer2 + _timer2, + #endif + _Nbr_16timers +} timer16_Sequence_t; diff --git a/Marlin/src/HAL/SAMD21/eeprom/QSPIFlash.cpp b/Marlin/src/HAL/SAMD21/eeprom/QSPIFlash.cpp new file mode 100644 index 0000000000..2a93226a6f --- /dev/null +++ b/Marlin/src/HAL/SAMD21/eeprom/QSPIFlash.cpp @@ -0,0 +1,82 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(QSPI_EEPROM) + +#include "QSPIFlash.h" + +#define INVALID_ADDR 0xFFFFFFFF +#define SECTOR_OF(a) (a & ~(SFLASH_SECTOR_SIZE - 1)) +#define OFFSET_OF(a) (a & (SFLASH_SECTOR_SIZE - 1)) + +Adafruit_SPIFlashBase * QSPIFlash::_flashBase = nullptr; +uint8_t QSPIFlash::_buf[SFLASH_SECTOR_SIZE]; +uint32_t QSPIFlash::_addr = INVALID_ADDR; + +void QSPIFlash::begin() { + if (_flashBase) return; + + _flashBase = new Adafruit_SPIFlashBase(new Adafruit_FlashTransport_QSPI()); + _flashBase->begin(nullptr); +} + +size_t QSPIFlash::size() { + return _flashBase->size(); +} + +uint8_t QSPIFlash::readByte(const uint32_t address) { + if (SECTOR_OF(address) == _addr) return _buf[OFFSET_OF(address)]; + + return _flashBase->read8(address); +} + +void QSPIFlash::writeByte(const uint32_t address, const uint8_t value) { + uint32_t const sector_addr = SECTOR_OF(address); + + // Page changes, flush old and update new cache + if (sector_addr != _addr) { + flush(); + _addr = sector_addr; + + // read a whole page from flash + _flashBase->readBuffer(sector_addr, _buf, SFLASH_SECTOR_SIZE); + } + + _buf[OFFSET_OF(address)] = value; +} + +void QSPIFlash::flush() { + if (_addr == INVALID_ADDR) return; + + _flashBase->eraseSector(_addr / SFLASH_SECTOR_SIZE); + _flashBase->writeBuffer(_addr, _buf, SFLASH_SECTOR_SIZE); + + _addr = INVALID_ADDR; +} + +#endif // QSPI_EEPROM diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD21/eeprom/QSPIFlash.h similarity index 100% rename from Marlin/src/HAL/SAMD51/QSPIFlash.h rename to Marlin/src/HAL/SAMD21/eeprom/QSPIFlash.h diff --git a/Marlin/src/HAL/SAMD21/eeprom/eeprom_flash.cpp b/Marlin/src/HAL/SAMD21/eeprom/eeprom_flash.cpp new file mode 100644 index 0000000000..0b5323cda4 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/eeprom/eeprom_flash.cpp @@ -0,0 +1,145 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#ifdef __SAMD21__ + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(FLASH_EEPROM_EMULATION) + +#define TOTAL_FLASH_SIZE (MARLIN_EEPROM_SIZE+255)/256*256 + +/* reserve flash memory */ +static const uint8_t flashdata[TOTAL_FLASH_SIZE] __attribute__((__aligned__(256))) { }; \ + +#include "../../shared/eeprom_api.h" + +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } + +/* +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } + const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, + sblk = NVMCTRL->SEESTAT.bit.SBLK; + + return ( + (!psz && !sblk) ? 0 + : (psz <= 2) ? (0x200 << psz) + : (sblk == 1 || psz == 3) ? 4096 + : (sblk == 2 || psz == 4) ? 8192 + : (sblk <= 4 || psz == 5) ? 16384 + : (sblk >= 9 && psz == 7) ? 65536 + : 32768 + ) - eeprom_exclude_size; +} +*/ + +uint32_t PAGE_SIZE; +uint32_t ROW_SIZE; +bool hasWritten = false; +uint8_t * buffer; + +void _erase(const volatile void *flash_ptr) { + NVMCTRL->ADDR.reg = ((uint32_t)flash_ptr) / 2; + NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_ER; + while (!NVMCTRL->INTFLAG.bit.READY) { } + +} + +void erase(const volatile void *flash_ptr, uint32_t size) { + const uint8_t *ptr = (const uint8_t *)flash_ptr; + while (size > ROW_SIZE) { + _erase(ptr); + ptr += ROW_SIZE; + size -= ROW_SIZE; + } + _erase(ptr); +} + +bool PersistentStore::access_start() { + /* clear page buffer*/ + NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC; + while (NVMCTRL->INTFLAG.bit.READY == 0) { } + + PAGE_SIZE = POW(2, 3 + NVMCTRL->PARAM.bit.PSZ); + ROW_SIZE= PAGE_SIZE * 4; + /*NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active + if (NVMCTRL->SEESTAT.bit.RLOCK) + NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); */ // Unlock E2P data write access + // erase(&flashdata[0], TOTAL_FLASH_SIZE); + return true; +} + +bool PersistentStore::access_finish() { + if (hasWritten) { + erase(&flashdata[0], TOTAL_FLASH_SIZE); + + NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC; + while (NVMCTRL->INTFLAG.bit.READY == 0) { } + + NVMCTRL->CTRLB.bit.MANW = 0; + + volatile uint32_t *dst_addr = (volatile uint32_t *) &flashdata; + + uint32_t *pointer = (uint32_t *) buffer; + for (uint32_t i = 0; i < TOTAL_FLASH_SIZE; i += 4) { + *dst_addr = (uint32_t) *pointer; + pointer++; + dst_addr ++; + } + + // Execute "WP" Write Page + NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_WP; + while (NVMCTRL->INTFLAG.bit.READY == 0) { } + + free(buffer); + hasWritten = false; + } + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + if (!hasWritten) { + // init temp buffer + buffer = (uint8_t *) malloc(MARLIN_EEPROM_SIZE); + hasWritten = true; + } + + memcpy(buffer + REAL_EEPROM_ADDR(pos), value, size); + pos += size; + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + volatile uint8_t *dst_addr = (volatile uint8_t *) &flashdata; + dst_addr += REAL_EEPROM_ADDR(pos); + + memcpy(value, (const void *)dst_addr, size); + pos += size; + return false; +} + +#endif // FLASH_EEPROM_EMULATION +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/eeprom/eeprom_qspi.cpp b/Marlin/src/HAL/SAMD21/eeprom/eeprom_qspi.cpp new file mode 100644 index 0000000000..8bd1bd3539 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/eeprom/eeprom_qspi.cpp @@ -0,0 +1,79 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#ifdef __SAMD21__ + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(QSPI_EEPROM) + +#error "QSPI_EEPROM emulation Not implemented on SAMD21" + +#include "../../shared/eeprom_api.h" + +#include "QSPIFlash.h" + +static bool initialized; + +size_t PersistentStore::capacity() { return qspi.size() - eeprom_exclude_size; } + +bool PersistentStore::access_start() { + if (!initialized) { + qspi.begin(); + initialized = true; + } + return true; +} + +bool PersistentStore::access_finish() { + qspi.flush(); + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + const uint8_t v = *value; + qspi.writeByte(REAL_EEPROM_ADDR(pos), v); + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + while (size--) { + const uint8_t c = qspi.readByte(REAL_EEPROM_ADDR(pos)); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } + return false; +} + +#endif // QSPI_EEPROM +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/eeprom/eeprom_wired.cpp b/Marlin/src/HAL/SAMD21/eeprom/eeprom_wired.cpp new file mode 100644 index 0000000000..82c701ebb1 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/eeprom/eeprom_wired.cpp @@ -0,0 +1,82 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#ifdef __SAMD21__ + +#include "../../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + +#error "USE_WIRED_EEPROM emulation Not implemented on SAMD21" +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } + +bool PersistentStore::access_start() { eeprom_init(); return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; + while (size--) { + const uint8_t v = *value; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! + eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + while (size--) { + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } + return false; +} + +#endif // USE_WIRED_EEPROM +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/endstop_interrupts.h b/Marlin/src/HAL/SAMD21/endstop_interrupts.h new file mode 100644 index 0000000000..8d8f9cd06f --- /dev/null +++ b/Marlin/src/HAL/SAMD21/endstop_interrupts.h @@ -0,0 +1,291 @@ +/** + * 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 + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +/** + * Endstop interrupts for ATMEL SAMD21 based targets. + * + * On SAMD21, all pins support external interrupt capability. + * Any pin can be used for external interrupts, but there are some restrictions. + * At most 16 different external interrupts can be used at one time. + * Further, you can't just pick any 16 pins to use. This is because every pin on the SAMD21 + * connects to what is called an EXTINT line, and only one pin per EXTINT line can be used for external + * interrupts at a time + */ + +/** + * Endstop Interrupts + * + * Without endstop interrupts the endstop pins must be polled continually in + * the temperature-ISR via endstops.update(), most of the time finding no change. + * With this feature endstops.update() is called only when we know that at + * least one endstop has changed state, saving valuable CPU cycles. + * + * This feature only works when all used endstop pins can generate an 'external interrupt'. + * + * Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'. + * (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino) + */ + +#include "../../module/endstops.h" + +#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) +#define MATCH_X_MAX_EILINE(P) TERN0(USE_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) +#define MATCH_X_MIN_EILINE(P) TERN0(USE_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) +#define MATCH_Y_MAX_EILINE(P) TERN0(USE_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) +#define MATCH_Y_MIN_EILINE(P) TERN0(USE_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) +#define MATCH_Z_MAX_EILINE(P) TERN0(USE_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) +#define MATCH_Z_MIN_EILINE(P) TERN0(USE_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) +#define MATCH_I_MAX_EILINE(P) TERN0(USE_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) +#define MATCH_I_MIN_EILINE(P) TERN0(USE_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) +#define MATCH_J_MAX_EILINE(P) TERN0(USE_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) +#define MATCH_J_MIN_EILINE(P) TERN0(USE_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) +#define MATCH_K_MAX_EILINE(P) TERN0(USE_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) +#define MATCH_K_MIN_EILINE(P) TERN0(USE_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) +#define MATCH_U_MAX_EILINE(P) TERN0(USE_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN)) +#define MATCH_U_MIN_EILINE(P) TERN0(USE_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN)) +#define MATCH_V_MAX_EILINE(P) TERN0(USE_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN)) +#define MATCH_V_MIN_EILINE(P) TERN0(USE_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN)) +#define MATCH_W_MAX_EILINE(P) TERN0(USE_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN)) +#define MATCH_W_MIN_EILINE(P) TERN0(USE_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN)) +#define MATCH_X2_MAX_EILINE(P) TERN0(USE_X2_MAX, DEFER4(MATCH_EILINE)(P, X2_MAX_PIN)) +#define MATCH_X2_MIN_EILINE(P) TERN0(USE_X2_MIN, DEFER4(MATCH_EILINE)(P, X2_MIN_PIN)) +#define MATCH_Y2_MAX_EILINE(P) TERN0(USE_Y2_MAX, DEFER4(MATCH_EILINE)(P, Y2_MAX_PIN)) +#define MATCH_Y2_MIN_EILINE(P) TERN0(USE_Y2_MIN, DEFER4(MATCH_EILINE)(P, Y2_MIN_PIN)) +#define MATCH_Z2_MAX_EILINE(P) TERN0(USE_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) +#define MATCH_Z2_MIN_EILINE(P) TERN0(USE_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) +#define MATCH_Z3_MAX_EILINE(P) TERN0(USE_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) +#define MATCH_Z3_MIN_EILINE(P) TERN0(USE_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) +#define MATCH_Z4_MAX_EILINE(P) TERN0(USE_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) +#define MATCH_Z4_MIN_EILINE(P) TERN0(USE_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) +#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(USE_Z_MIN_PROBE, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) +#define MATCH_CALIBRATION_EILINE(P) TERN0(USE_CALIBRATION, DEFER4(MATCH_EILINE)(P, CALIBRATION_PIN)) + +#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \ + && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ + && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \ + && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \ + && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P) \ + && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P) \ + && !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P) \ + && !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P) \ + && !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P) \ + && !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P) \ + && !MATCH_X2_MAX_EILINE(P) && !MATCH_X2_MIN_EILINE(P) \ + && !MATCH_Y2_MAX_EILINE(P) && !MATCH_Y2_MIN_EILINE(P) \ + && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ + && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ + && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ + && !MATCH_Z_MIN_PROBE_EILINE(P) \ + && !MATCH_CALIBRATION_EILINE(P) ) + +// One ISR for all EXT-Interrupts +void endstop_ISR() { endstops.update(); } + +void setup_endstop_interrupts() { + #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) + #if USE_X_MAX + #if !AVAILABLE_EILINE(X_MAX_PIN) + #error "X_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X_MAX_PIN); + #endif + #if USE_X_MIN + #if !AVAILABLE_EILINE(X_MIN_PIN) + #error "X_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X_MIN_PIN); + #endif + #if USE_Y_MAX + #if !AVAILABLE_EILINE(Y_MAX_PIN) + #error "Y_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y_MAX_PIN); + #endif + #if USE_Y_MIN + #if !AVAILABLE_EILINE(Y_MIN_PIN) + #error "Y_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y_MIN_PIN); + #endif + #if USE_Z_MAX + #if !AVAILABLE_EILINE(Z_MAX_PIN) + #error "Z_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z_MAX_PIN); + #endif + #if USE_Z_MIN + #if !AVAILABLE_EILINE(Z_MIN_PIN) + #error "Z_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z_MIN_PIN); + #endif + #if USE_X2_MAX + #if !AVAILABLE_EILINE(X2_MAX_PIN) + #error "X2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X2_MAX_PIN); + #endif + #if USE_X2_MIN + #if !AVAILABLE_EILINE(X2_MIN_PIN) + #error "X2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X2_MIN_PIN); + #endif + #if USE_Y2_MAX + #if !AVAILABLE_EILINE(Y2_MAX_PIN) + #error "Y2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y2_MAX_PIN); + #endif + #if USE_Y2_MIN + #if !AVAILABLE_EILINE(Y2_MIN_PIN) + #error "Y2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y2_MIN_PIN); + #endif + #if USE_Z2_MAX + #if !AVAILABLE_EILINE(Z2_MAX_PIN) + #error "Z2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z2_MAX_PIN); + #endif + #if USE_Z2_MIN + #if !AVAILABLE_EILINE(Z2_MIN_PIN) + #error "Z2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z2_MIN_PIN); + #endif + #if USE_Z3_MAX + #if !AVAILABLE_EILINE(Z3_MAX_PIN) + #error "Z3_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z3_MAX_PIN); + #endif + #if USE_Z3_MIN + #if !AVAILABLE_EILINE(Z3_MIN_PIN) + #error "Z3_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z3_MIN_PIN); + #endif + #if USE_Z4_MAX + #if !AVAILABLE_EILINE(Z4_MAX_PIN) + #error "Z4_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z4_MAX_PIN); + #endif + #if USE_Z4_MIN + #if !AVAILABLE_EILINE(Z4_MIN_PIN) + #error "Z4_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z4_MIN_PIN); + #endif + #if USE_Z_MIN_PROBE + #if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN) + #error "Z_MIN_PROBE_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Z_MIN_PROBE_PIN); + #endif + #if USE_CALIBRATION + #if !AVAILABLE_EILINE(CALIBRATION_PIN) + #error "CALIBRATION_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(CALIBRATION_PIN); + #endif + #if USE_I_MAX + #if !AVAILABLE_EILINE(I_MAX_PIN) + #error "I_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); + #endif + #if USE_I_MIN + #if !AVAILABLE_EILINE(I_MIN_PIN) + #error "I_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if USE_J_MAX + #if !AVAILABLE_EILINE(J_MAX_PIN) + #error "J_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); + #endif + #if USE_J_MIN + #if !AVAILABLE_EILINE(J_MIN_PIN) + #error "J_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if USE_K_MAX + #if !AVAILABLE_EILINE(K_MAX_PIN) + #error "K_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); + #endif + #if USE_K_MIN + #if !AVAILABLE_EILINE(K_MIN_PIN) + #error "K_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if USE_U_MAX + #if !AVAILABLE_EILINE(U_MAX_PIN) + #error "U_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE); + #endif + #if USE_U_MIN + #if !AVAILABLE_EILINE(U_MIN_PIN) + #error "U_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if USE_V_MAX + #if !AVAILABLE_EILINE(V_MAX_PIN) + #error "V_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE); + #endif + #if USE_V_MIN + #if !AVAILABLE_EILINE(V_MIN_PIN) + #error "V_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if USE_W_MAX + #if !AVAILABLE_EILINE(W_MAX_PIN) + #error "W_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE); + #endif + #if USE_W_MIN + #if !AVAILABLE_EILINE(W_MIN_PIN) + #error "W_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE); + #endif +} diff --git a/Marlin/src/HAL/SAMD21/fastio.h b/Marlin/src/HAL/SAMD21/fastio.h new file mode 100644 index 0000000000..32cc557528 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/fastio.h @@ -0,0 +1,215 @@ +/** + * 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 + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +/** + * Fast IO functions for SAMD21 + */ + +#include "SAMD21.h" + +/** + * Utility functions + */ + +#ifndef MASK + #define MASK(PIN) _BV(PIN) +#endif + +/** + * Magic I/O routines + * + * Now you can simply SET_OUTPUT(IO); WRITE(IO, HIGH); WRITE(IO, LOW); + */ + +// Read a pin +#define READ(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].IN.reg & MASK(GET_SAMD_PIN(IO))) != 0) + +// Write to a pin +#define WRITE(IO,V) do{ \ + const EPortType port = (EPortType)GET_SAMD_PORT(IO); \ + const uint32_t mask = MASK(GET_SAMD_PIN(IO)); \ + \ + if (V) PORT->Group[port].OUTSET.reg = mask; \ + else PORT->Group[port].OUTCLR.reg = mask; \ + }while(0) + +// Toggle a pin +#define TOGGLE(IO) PORT->Group[(EPortType)GET_SAMD_PORT(IO)].OUTTGL.reg = MASK(GET_SAMD_PIN(IO)); + +// Set pin as input +#define SET_INPUT(IO) do{ \ + const EPortType port = (EPortType)GET_SAMD_PORT(IO); \ + const uint32_t pin = GET_SAMD_PIN(IO); \ + \ + PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN); \ + PORT->Group[port].DIRCLR.reg = MASK(pin); \ + }while(0) +// Set pin as input with pullup +#define SET_INPUT_PULLUP(IO) do{ \ + const EPortType port = (EPortType)GET_SAMD_PORT(IO); \ + const uint32_t pin = GET_SAMD_PIN(IO); \ + const uint32_t mask = MASK(pin); \ + \ + PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN | PORT_PINCFG_PULLEN); \ + PORT->Group[port].DIRCLR.reg = mask; \ + PORT->Group[port].OUTSET.reg = mask; \ + }while(0) +// Set pin as input with pulldown +#define SET_INPUT_PULLDOWN(IO) do{ \ + const EPortType port = (EPortType)GET_SAMD_PORT(IO); \ + const uint32_t pin = GET_SAMD_PIN(IO); \ + const uint32_t mask = MASK(pin); \ + \ + PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN | PORT_PINCFG_PULLEN); \ + PORT->Group[port].DIRCLR.reg = mask; \ + PORT->Group[port].OUTCLR.reg = mask; \ + }while(0) +// Set pin as output (push pull) +#define SET_OUTPUT(IO) do{ \ + const EPortType port = (EPortType)GET_SAMD_PORT(IO); \ + const uint32_t pin = GET_SAMD_PIN(IO); \ + \ + PORT->Group[port].DIRSET.reg = MASK(pin); \ + PORT->Group[port].PINCFG[pin].reg = 0; \ + }while(0) +// Set pin as output (open drain) +#define SET_OUTPUT_OD(IO) do{ \ + const EPortType port = (EPortType)GET_SAMD_PORT(IO); \ + const uint32_t pin = GET_SAMD_PIN(IO); \ + \ + PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_PULLEN); \ + PORT->Group[port].DIRCLR.reg = MASK(pin); \ + }while(0) +// Set pin as PWM (push pull) +#define SET_PWM SET_OUTPUT +// Set pin as PWM (open drain) +#define SET_PWM_OD SET_OUTPUT_OD + +// check if pin is an output +#define IS_OUTPUT(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].DIR.reg & MASK(GET_SAMD_PIN(IO))) \ + || (PORT->Group[(EPortType)GET_SAMD_PORT(IO)].PINCFG[GET_SAMD_PIN(IO)].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN) +// check if pin is an input +#define IS_INPUT(IO) !IS_OUTPUT(IO) + +// Shorthand +#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0) +#define OUT_WRITE_OD(IO,V) do{ SET_OUTPUT_OD(IO); WRITE(IO,V); }while(0) + +// digitalRead/Write wrappers +#define extDigitalRead(IO) digitalRead(IO) +#define extDigitalWrite(IO,V) digitalWrite(IO,V) + +/** + * Ports and functions + * Added as necessary or if I feel like it- not a comprehensive list! + */ + +/** + * Some of these share the same source and so can't be used in the same time + */ +#define PWM_PIN(P) (WITHIN(P, 2, 13) || WITHIN(P, 22, 23) || WITHIN(P, 44, 45) || P == 48) + +// Return fulfilled ADCx->INPUTCTRL.reg +#define PIN_TO_INPUTCTRL(P) ( (P == 0) ? ADC_INPUTCTRL_MUXPOS_PIN0 \ + : ((P) == 1) ? ADC_INPUTCTRL_MUXPOS_PIN1 \ + : ((P) == 2) ? ADC_INPUTCTRL_MUXPOS_PIN3 \ + : ((P) == 3) ? ADC_INPUTCTRL_MUXPOS_PIN4 \ + : ((P) == 4) ? ADC_INPUTCTRL_MUXPOS_PIN5 \ + : ((P) == 5) ? ADC_INPUTCTRL_MUXPOS_PIN5 \ + : ((P) == 6) ? ADC_INPUTCTRL_MUXPOS_PIN6 \ + : ((P) == 7) ? ADC_INPUTCTRL_MUXPOS_PIN7 \ + : ((P) == 8) ? ADC_INPUTCTRL_MUXPOS_PIN8 \ + : ((P) == 9) ? ADC_INPUTCTRL_MUXPOS_PIN9 \ + : ((P) == 10) ? ADC_INPUTCTRL_MUXPOS_PIN10 \ + : ((P) == 11) ? ADC_INPUTCTRL_MUXPOS_PIN11 \ + : ((P) == 12) ? ADC_INPUTCTRL_MUXPOS_PIN12 \ + : ((P) == 13) ? ADC_INPUTCTRL_MUXPOS_PIN13 \ + : ((P) == 14) ? ADC_INPUTCTRL_MUXPOS_PIN14 \ + : ADC_INPUTCTRL_MUXPOS_PIN15) + +#define digitalPinToAnalogIndex(P) (WITHIN(P, 67, 74) ? (P) - 67 : WITHIN(P, 54, 61) ? 8 + (P) - 54 : WITHIN(P, 12, 13) ? 16 + (P) - 12 : P == 9 ? 18 : -1) + +/** + * pins + */ + +// PORTA +#define DIO28_PIN PIN_PA02 // A0 +#define DIO56_PIN PIN_PA03 // A13 +#define DIO31_PIN PIN_PA04 // A13 +#define DIO32_PIN PIN_PA05 // A1 +#define DIO8_PIN PIN_PA06 // A14 +#define DIO9_PIN PIN_PA07 // A15 +#define DIO4_PIN PIN_PA08 // A15 +#define DIO3_PIN PIN_PA09 // A15 +#define DIO1_PIN PIN_PA10 +#define DIO0_PIN PIN_PA11 +#define DIO18_PIN PIN_PA12 +#define DIO52_PIN PIN_PA13 +#define DIO2_PIN PIN_PA14 +#define DIO5_PIN PIN_PA15 +#define DIO11_PIN PIN_PA16 +#define DIO13_PIN PIN_PA17 +#define DIO10_PIN PIN_PA18 +#define DIO12_PIN PIN_PA19 +#define DIO6_PIN PIN_PA20 +#define DIO07_PIN PIN_PA21 +#define DIO34_PIN PIN_PA22 +#define DIO35_PIN PIN_PA23 +#define DIO42_PIN PIN_PA24 +#define DIO43_PIN PIN_PA25 + +#define DIO40_PIN PIN_PA27 + +#define DIO26_PIN PIN_PB00 +#define DIO27_PIN PIN_PB01 // A0 +#define DIO33_PIN PIN_PB02 +#define DIO39_PIN PIN_PB03 +#define DIO14_PIN PIN_PB04 +#define DIO15_PIN PIN_PB05 +#define DIO16_PIN PIN_PB06 +#define DIO17_PIN PIN_PB07 +#define DIO29_PIN PIN_PB08 +#define DIO30_PIN PIN_PB09 +#define DIO37_PIN PIN_PB10 +#define DIO38_PIN PIN_PB11 +#define DIO36_PIN PIN_PB12 +#define DIO19_PIN PIN_PB13 +#define DIO20_PIN PIN_PB14 +#define DIO21_PIN PIN_PB15 +#define DIO22_PIN PIN_PB16 +#define DIO23_PIN PIN_PB17 + +#define DIO44_PIN PIN_PB22 +#define DIO45_PIN PIN_PB23 +#define DIO24_PIN PIN_PB30 +#define DIO25_PIN PIN_PB31 + +#define DIO53_PIN PIN_PA21 +#define DIO54_PIN PIN_PA06 +#define DIO55_PIN PIN_PA07 diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h new file mode 100644 index 0000000000..570baf7e95 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h @@ -0,0 +1,22 @@ +/** + * 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 diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_adv.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_adv.h new file mode 100644 index 0000000000..d6a3c4fe0b --- /dev/null +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_adv.h @@ -0,0 +1,27 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#pragma once diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h new file mode 100644 index 0000000000..87d3350c94 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h @@ -0,0 +1,33 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#pragma once + +#if USE_FALLBACK_EEPROM + #define FLASH_EEPROM_EMULATION +#elif ANY(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 +#endif diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_type.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/SAMD21/inc/SanityCheck.h b/Marlin/src/HAL/SAMD21/inc/SanityCheck.h new file mode 100644 index 0000000000..83fafc9689 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/inc/SanityCheck.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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +/** + * Test SAMD21 specific configuration values for errors at compile-time. + */ + +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for HAL/SAMD21." +#endif + +#if SERVO_TC == MF_TIMER_RTC + #error "Servos can't use RTC timer" +#endif + +#if ENABLED(EMERGENCY_PARSER) + #error "EMERGENCY_PARSER is not yet implemented for SAMD21. Disable EMERGENCY_PARSER to continue." +#endif + +#if ENABLED(ONBOARD_SDIO) + #error "ONBOARD_SDIO is not supported on SAMD21." +#endif + +#if ENABLED(FAST_PWM_FAN) + #error "Features requiring Hardware PWM (FAST_PWM_FAN) are not yet supported for HAL/SAMD21." +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on SAMD21." +#endif diff --git a/Marlin/src/HAL/SAMD21/pinsDebug.h b/Marlin/src/HAL/SAMD21/pinsDebug.h new file mode 100644 index 0000000000..387516aa79 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/pinsDebug.h @@ -0,0 +1,175 @@ +/** + * 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 + +/** + * Pins Debugging for SAMD21 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + +#define NUMBER_PINS_TOTAL PINS_COUNT + +#define digitalRead_mod(P) extDigitalRead(P) +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define getPinByIndex(x) pin_array[x].pin +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL)) +#define isAnalogPin(P) (digitalPinToAnalogIndex(P) != -1) +#define pwm_status(P) digitalPinHasPWM(P) +#define MULTI_NAME_PAD 27 // space needed to be pretty if not first name assigned to a pin + +// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities +// uses pin index +#define M43_NEVER_TOUCH(Q) ((Q) >= 75) + +bool getValidPinMode(const int8_t pin) { // 1: output, 0: input + const EPortType samdport = g_APinDescription[pin].ulPort; + const uint32_t samdpin = g_APinDescription[pin].ulPin; + return PORT->Group[samdport].DIR.reg & MASK(samdpin) || (PORT->Group[samdport].PINCFG[samdpin].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN; +} + +void printPinPWM(const int32_t pin) { + if (pwm_status(pin)) { + //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative; + //SERIAL_ECHOPGM("PWM = ", duty); + } +} + +void printPinPort(const pin_t) {} + +/** + * SAMD21 Board pin| PORT | Label + * ----------------+--------+------- + * 0 | PB25 | "RX0" + * 1 | PB24 | "TX0" + * 2 | PC18 | + * 3 | PC19 | + * 4 | PC20 | + * 5 | PC21 | + * 6 | PD20 | + * 7 | PD21 | + * 8 | PB18 | + * 9 | PB2 | + * 10 | PB22 | + * 11 | PB23 | + * 12 | PB0 | "A16" + * 13 | PB1 | LED AMBER "L" / "A17" + * 14 | PB16 | "TX3" + * 15 | PB17 | "RX3" + * 16 | PC22 | "TX2" + * 17 | PC23 | "RX2" + * 18 | PB12 | "TX1" / "A18" + * 19 | PB13 | "RX1" + * 20 | PB20 | "SDA" + * 21 | PB21 | "SCL" + * 22 | PD12 | + * 23 | PA15 | + * 24 | PC17 | + * 25 | PC16 | + * 26 | PA12 | + * 27 | PA13 | + * 28 | PA14 | + * 29 | PB19 | + * 30 | PA23 | + * 31 | PA22 | + * 32 | PA21 | + * 33 | PA20 | + * 34 | PA19 | + * 35 | PA18 | + * 36 | PA17 | + * 37 | PA16 | + * 38 | PB15 | + * 39 | PB14 | + * 40 | PC13 | + * 41 | PC12 | + * 42 | PC15 | + * 43 | PC14 | + * 44 | PC11 | + * 45 | PC10 | + * 46 | PC6 | + * 47 | PC7 | + * 48 | PC4 | + * 49 | PC5 | + * 50 | PD11 | + * 51 | PD8 | + * 52 | PD9 | + * 53 | PD10 | + * 54 | PB5 | "A8" + * 55 | PB6 | "A9" + * 56 | PB7 | "A10" + * 57 | PB8 | "A11" + * 58 | PB9 | "A12" + * 69 | PA4 | "A13" + * 60 | PA6 | "A14" + * 61 | PA7 | "A15" + * 62 | PB17 | + * 63 | PB20 | + * 64 | PD11 | + * 65 | PD8 | + * 66 | PD9 | + * 67 | PA2 | "A0" / "DAC0" + * 68 | PA5 | "A1" / "DAC1" + * 69 | PB3 | "A2" + * 70 | PC0 | "A3" + * 71 | PC1 | "A4" + * 72 | PC2 | "A5" + * 73 | PC3 | "A6" + * 74 | PB4 | "A7" + * 75 | PC31 | LED GREEN "RX" + * 76 | PC30 | LED GREEN "TX" + * 77 | PA27 | USB: Host enable + * 78 | PA24 | USB: D- + * 79 | PA25 | USB: D+ + * 80 | PB29 | SD: MISO + * 81 | PB27 | SD: SCK + * 82 | PB26 | SD: MOSI + * 83 | PB28 | SD: CS + * 84 | PA3 | AREF + * 85 | PA2 | DAC0 (Duplicate) + * 86 | PA5 | DAC1 (Duplicate) + * 87 | PB1 | LED AMBER "L" (Duplicate) + * 88 | PC24 | NeoPixel + * 89 | PB10 | QSPI: SCK + * 90 | PB11 | QSPI: CS + * 91 | PA8 | QSPI: IO0 + * 92 | PA9 | QSPI: IO1 + * 93 | PA10 | QSPI: IO2 + * 94 | PA11 | QSPI: IO3 + * 95 | PB31 | SD: DETECT + */ diff --git a/Marlin/src/HAL/SAMD21/spi_pins.h b/Marlin/src/HAL/SAMD21/spi_pins.h new file mode 100644 index 0000000000..1186c3de48 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/spi_pins.h @@ -0,0 +1,47 @@ +/** + * 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 + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +/** + * SAMD21 Default SPI Pins + * + * SS SCK MISO MOSI + * +-------------------------+ + * SPI | 53 52 50 51 | + * SPI1 | 83 81 80 82 | + * +-------------------------+ + * Any pin can be used for Chip Select (SD_SS_PIN) + */ +#ifndef SD_SCK_PIN + #define SD_SCK_PIN 38 +#endif +#ifndef SD_MISO_PIN + #define SD_MISO_PIN 36 +#endif +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN 37 +#endif diff --git a/Marlin/src/HAL/SAMD21/timers.cpp b/Marlin/src/HAL/SAMD21/timers.cpp new file mode 100644 index 0000000000..21a1767fc0 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/timers.cpp @@ -0,0 +1,217 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#ifdef __SAMD21__ + +// -------------------------------------------------------------------------- +// Includes +// -------------------------------------------------------------------------- + +#include "../../inc/MarlinConfig.h" +#include "ServoTimers.h" // for SERVO_TC + +// -------------------------------------------------------------------------- +// Local defines +// -------------------------------------------------------------------------- + +#define NUM_HARDWARE_TIMERS 9 + +// -------------------------------------------------------------------------- +// Private Variables +// -------------------------------------------------------------------------- + +const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = { + { {.pTcc=TCC0}, TimerType::tcc, TCC0_IRQn, TC_PRIORITY(0) }, // 0 - stepper (assigned priority 2) + { {.pTcc=TCC1}, TimerType::tcc, TCC1_IRQn, TC_PRIORITY(1) }, // 1 - stepper (needed by 32 bit timers) + { {.pTcc=TCC2}, TimerType::tcc, TCC2_IRQn, 5 }, // 2 - tone (reserved by framework and fixed assigned priority 5) + { {.pTc=TC3}, TimerType::tc, TC3_IRQn, TC_PRIORITY(3) }, // 3 - servo (assigned priority 1) + { {.pTc=TC4}, TimerType::tc, TC4_IRQn, TC_PRIORITY(4) }, // 4 - software serial (no interrupts used) + { {.pTc=TC5}, TimerType::tc, TC5_IRQn, TC_PRIORITY(5) }, + { {.pTc=TC6}, TimerType::tc, TC6_IRQn, TC_PRIORITY(6) }, + { {.pTc=TC7}, TimerType::tc, TC7_IRQn, TC_PRIORITY(7) }, + { {.pRtc=RTC}, TimerType::rtc, RTC_IRQn, TC_PRIORITY(8) } // 8 - temperature (assigned priority 6) +}; + +// -------------------------------------------------------------------------- +// Private functions +// -------------------------------------------------------------------------- + +FORCE_INLINE void Disable_Irq(IRQn_Type irq) { + NVIC_DisableIRQ(irq); + + // 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(); +} + +static bool tcIsSyncing(Tc * tc) { + return tc->COUNT32.STATUS.reg & TC_STATUS_SYNCBUSY; +} + +static void tcReset( Tc * tc) { + tc->COUNT32.CTRLA.reg = TC_CTRLA_SWRST; + while (tcIsSyncing(tc)) {} + while (tc->COUNT32.CTRLA.bit.SWRST) {} +} + +// -------------------------------------------------------------------------- +// Public functions +// -------------------------------------------------------------------------- + +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { + IRQn_Type irq = timer_config[timer_num].IRQ_Id; + + // Disable interrupt, just in case it was already enabled + NVIC_DisableIRQ(irq); + NVIC_ClearPendingIRQ(irq); + + if (timer_num == MF_TIMER_RTC) { + + // https://github.com/arduino-libraries/RTCZero + Rtc * const rtc = timer_config[timer_num].pRtc; + PM->APBAMASK.reg |= PM_APBAMASK_RTC; + + GCLK->CLKCTRL.reg = (uint32_t)((GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK4 | (RTC_GCLK_ID << GCLK_CLKCTRL_ID_Pos))); + while (GCLK->STATUS.bit.SYNCBUSY) {} + + GCLK->GENCTRL.reg = (GCLK_GENCTRL_GENEN | GCLK_GENCTRL_SRC_OSCULP32K | GCLK_GENCTRL_ID(4) | GCLK_GENCTRL_DIVSEL ); + while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} + + GCLK->GENDIV.reg = GCLK_GENDIV_ID(4); + GCLK->GENDIV.bit.DIV=4; + while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} + + // Disable timer interrupt + rtc->MODE0.INTENCLR.reg = RTC_MODE0_INTENCLR_CMP0; + SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY); + + while(rtc->MODE0.STATUS.bit.SYNCBUSY) {} + + // Stop timer, just in case, to be able to reconfigure it + rtc->MODE0.CTRL.reg = + RTC_MODE0_CTRL_MODE_COUNT32 | // Mode 0 = 32-bits counter + RTC_MODE0_CTRL_PRESCALER_DIV1024; // Divisor = 1024 + + while(rtc->MODE0.STATUS.bit.SYNCBUSY) {} + + // Mode, reset counter on match + rtc->MODE0.CTRL.reg = RTC_MODE0_CTRL_MODE_COUNT32 | RTC_MODE0_CTRL_MATCHCLR; + + // Set compare value + rtc->MODE0.COMP[0].reg = (32768 + frequency / 2) / frequency; + SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY); + + // Enable interrupt on compare + rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0; // reset pending interrupt + rtc->MODE0.INTENSET.reg = RTC_MODE0_INTENSET_CMP0; // enable compare 0 interrupt + + // And start timer + rtc->MODE0.CTRL.bit.ENABLE = true; + SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY); + + } + else if (timer_config[timer_num].type==TimerType::tcc) { + + Tcc * const tc = timer_config[timer_num].pTcc; + + PM->APBCMASK.reg |= PM_APBCMASK_TCC0; + GCLK->CLKCTRL.reg =(GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(TCC0_GCLK_ID)); + SYNC (GCLK->STATUS.bit.SYNCBUSY); + + tc->CTRLA.reg = TCC_CTRLA_SWRST; + SYNC (tc->SYNCBUSY.reg & TCC_SYNCBUSY_SWRST) {} + + SYNC (tc->CTRLA.bit.SWRST); + + tc->CTRLA.reg &= ~(TCC_CTRLA_ENABLE); // disable TC module + + tc->CTRLA.reg |= TCC_WAVE_WAVEGEN_MFRQ; + tc->CTRLA.reg |= TCC_CTRLA_PRESCALER_DIV2; + tc->CC[0].reg = (HAL_TIMER_RATE) / frequency; + tc->INTENSET.reg = TCC_INTFLAG_MC0; + tc->CTRLA.reg |= TCC_CTRLA_ENABLE; + tc->INTFLAG.reg = 0xFF; + SYNC ( tc->STATUS.reg & TC_STATUS_SYNCBUSY); + + } + else { + Tc * const tc = timer_config[timer_num].pTc; + + // Disable timer interrupt + tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt + + // TCn clock setup + GCLK->CLKCTRL.reg = uint16_t(GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_TC4_TC5)); + SYNC (GCLK->STATUS.bit.SYNCBUSY); + + tcReset(tc); // reset TC + + // Set Timer counter 5 Mode to 16 bits, it will become a 16bit counter ('mode1' in the datasheet) + tc->COUNT32.CTRLA.reg |= TC_CTRLA_MODE_COUNT32; + // Set TC waveform generation mode to 'match frequency' + tc->COUNT32.CTRLA.reg |= TC_CTRLA_WAVEGEN_MFRQ; + //set prescaler + //the clock normally counts at the GCLK_TC frequency, but we can set it to divide that frequency to slow it down + //you can use different prescaler divisions here like TC_CTRLA_PRESCALER_DIV1 to get a different range + tc->COUNT32.CTRLA.reg |= TC_CTRLA_PRESCALER_DIV1 | TC_CTRLA_ENABLE; //it will divide GCLK_TC frequency by 1024 + //set the compare-capture register. + //The counter will count up to this value (it's a 16bit counter so we use uint16_t) + //this is how we fine-tune the frequency, make it count to a lower or higher value + //system clock should be 1MHz (8MHz/8) at Reset by default + tc->COUNT32.CC[0].reg = (uint16_t) (HAL_TIMER_RATE / frequency); + while (tcIsSyncing(tc)) {} + + // Enable the TC interrupt request + tc->COUNT32.INTENSET.bit.MC0 = 1; + while (tcIsSyncing(tc)) {} + } + + NVIC_SetPriority(irq, timer_config[timer_num].priority); + NVIC_EnableIRQ(irq); +} + +void HAL_timer_enable_interrupt(const uint8_t timer_num) { + const IRQn_Type irq = timer_config[timer_num].IRQ_Id; + NVIC_EnableIRQ(irq); +} + +void HAL_timer_disable_interrupt(const uint8_t timer_num) { + const IRQn_Type irq = timer_config[timer_num].IRQ_Id; + Disable_Irq(irq); +} + +// missing from CMSIS: Check if interrupt is enabled or not +static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) { + return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F); +} + +bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { + const IRQn_Type irq = timer_config[timer_num].IRQ_Id; + return NVIC_GetEnabledIRQ(irq); +} + +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/timers.h b/Marlin/src/HAL/SAMD21/timers.h new file mode 100644 index 0000000000..dfae605595 --- /dev/null +++ b/Marlin/src/HAL/SAMD21/timers.h @@ -0,0 +1,158 @@ +/** + * 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 + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +#include + +// -------------------------------------------------------------------------- +// Defines +// -------------------------------------------------------------------------- + +typedef uint32_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) + +#define HAL_TIMER_RATE F_CPU // frequency of timers peripherals + +#define MF_TIMER_RTC 8 // This is not a TC but a RTC + +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 4 // Timer Index for Stepper +#endif +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP +#endif +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP MF_TIMER_RTC // Timer Index for Temperature +#endif + +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency + +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) + +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE + +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) + +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) + +#define TC_PRIORITY(t) ( t == SERVO_TC ? 1 \ + : (t == MF_TIMER_STEP || t == MF_TIMER_PULSE) ? 2 \ + : (t == MF_TIMER_TEMP) ? 6 : 7 ) + +#define _TC_HANDLER(t) void TC##t##_Handler() +#define TC_HANDLER(t) _TC_HANDLER(t) +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() TC_HANDLER(MF_TIMER_STEP) +#endif +#if MF_TIMER_STEP != MF_TIMER_PULSE + #define HAL_PULSE_TIMER_ISR() TC_HANDLER(MF_TIMER_PULSE) +#endif +#if MF_TIMER_TEMP == MF_TIMER_RTC + #define HAL_TEMP_TIMER_ISR() void RTC_Handler() +#else + #define HAL_TEMP_TIMER_ISR() TC_HANDLER(MF_TIMER_TEMP) +#endif + +// -------------------------------------------------------------------------- +// Types +// -------------------------------------------------------------------------- +typedef enum { tcc, tc, rtc } TimerType; + +typedef struct { + union { + Tc *pTc; + Tcc *pTcc; + Rtc *pRtc; + }; + TimerType type; + IRQn_Type IRQ_Id; + uint8_t priority; +} tTimerConfig; + +// -------------------------------------------------------------------------- +// Public Variables +// -------------------------------------------------------------------------- + +extern const tTimerConfig timer_config[]; + +// -------------------------------------------------------------------------- +// Public functions +// -------------------------------------------------------------------------- + +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); + +FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { + // Should never be called with timer MF_TIMER_RTC + Tc * const tc = timer_config[timer_num].pTc; + tc->COUNT32.CC[0].reg = compare; +} + +FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { + // Should never be called with timer MF_TIMER_RTC + Tc * const tc = timer_config[timer_num].pTc; + return (hal_timer_t)tc->COUNT32.CC[0].reg; +} + +FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { + // Should never be called with timer MF_TIMER_RTC + Tc * const tc = timer_config[timer_num].pTc; + tc->COUNT32.READREQ.reg = TC_READREQ_RREQ; + // Request a read synchronization + SYNC (tc->COUNT32.STATUS.bit.SYNCBUSY); + //SYNC(tc->COUNT32.STATUS.bit.SYNCBUSY ); + return tc->COUNT32.COUNT.reg; +} + +void HAL_timer_enable_interrupt(const uint8_t timer_num); +void HAL_timer_disable_interrupt(const uint8_t timer_num); +bool HAL_timer_interrupt_enabled(const uint8_t timer_num); + +FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { + if (timer_num == MF_TIMER_RTC) { + Rtc * const rtc = timer_config[timer_num].pRtc; + // Clear interrupt flag + rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0| RTC_MODE0_INTFLAG_OVF; + } + else if (timer_config[timer_num].type == TimerType::tcc) { + Tcc * const tc = timer_config[timer_num].pTcc; + // Clear interrupt flag + tc->INTFLAG.reg = TCC_INTFLAG_OVF; + } + else { + Tc * const tc = timer_config[timer_num].pTc; + // Clear interrupt flag + tc->COUNT32.INTFLAG.bit.MC0 = 1; + } +} + +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.cpp b/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.cpp new file mode 100644 index 0000000000..7cbedd84fc --- /dev/null +++ b/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.cpp @@ -0,0 +1,32 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +// adapted from I2C/master/master.c example +// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html + +#ifdef __SAMD21__ + +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.h b/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.h new file mode 100644 index 0000000000..d6a3c4fe0b --- /dev/null +++ b/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.h @@ -0,0 +1,27 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#pragma once diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_defines.h b/Marlin/src/HAL/SAMD21/u8g/LCD_defines.h new file mode 100644 index 0000000000..d6fe93117b --- /dev/null +++ b/Marlin/src/HAL/SAMD21/u8g/LCD_defines.h @@ -0,0 +1,29 @@ +/** + * 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 + +/** + * SAMD21 LCD-specific defines + */ + +uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); +#define U8G_COM_ST7920_HAL_HW_SPI u8g_com_samd21_st7920_hw_spi_fn diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.c b/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.c new file mode 100644 index 0000000000..b2079fef9b --- /dev/null +++ b/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.c @@ -0,0 +1,42 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +/** + * Low level pin manipulation routines - used by all the drivers. + * + * These are based on the SAMD51 pinMode, digitalRead & digitalWrite routines. + * + * Couldn't just call exact copies because the overhead killed the LCD update speed + * With an intermediate level the softspi was running in the 10-20kHz range which + * resulted in using about 25% of the CPU's time. + */ + +#ifdef __SAMD21__ + +#include + +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.h b/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.h new file mode 100644 index 0000000000..a4bf2800fe --- /dev/null +++ b/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.h @@ -0,0 +1,42 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ +#pragma once + +/** + * Low level pin manipulation routines - used by all the drivers. + * + * These are based on the SAMD51 pinMode, digitalRead & digitalWrite routines. + * + * Couldn't just call exact copies because the overhead killed the LCD update speed + * With an intermediate level the softspi was running in the 10-20kHz range which + * resulted in using about 25% of the CPU's time. + */ + +void u8g_SetPinOutput(uint8_t internal_pin_number); +void u8g_SetPinInput(uint8_t internal_pin_number); +void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status); +uint8_t u8g_GetPinLevel(uint8_t pin); diff --git a/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp b/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp new file mode 100644 index 0000000000..2e2b0d8f8d --- /dev/null +++ b/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp @@ -0,0 +1,157 @@ +/** + * 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 . + * + */ + +/** + * SAMD21 HAL developed by Bart Meijer (brupje) + * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) + */ + +/** + * Based on u8g_com_msp430_hw_spi.c + * + * Universal 8bit Graphics Library + * + * Copyright (c) 2012, olikraus@gmail.com + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or other + * materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifdef __SAMD21__ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_MARLINUI_U8GLIB + +#include +#include "SPI.h" + +#include "../../shared/HAL_SPI.h" + +#ifndef LCD_SPI_SPEED + #define LCD_SPI_SPEED SPI_HALF_SPEED +#endif + +void u8g_SetPIOutput(u8g_t *u8g, uint8_t pin_index) { + if (u8g->pin_list[pin_index]!= U8G_PIN_NONE) + pinMode(u8g->pin_list[pin_index],OUTPUT); +} + +void u8g_SetPILevel(u8g_t *u8g, uint8_t pin_index, uint8_t level) { + if (u8g->pin_list[pin_index]!= U8G_PIN_NONE) + digitalWrite(u8g->pin_list[pin_index],level); +} + +uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + + switch (msg) { + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_INIT: + u8g_SetPIOutput(u8g, U8G_PI_CS); + u8g_SetPIOutput(u8g, U8G_PI_A0); + u8g_SetPIOutput(u8g, U8G_PI_RESET); + + u8g_SetPILevel(u8g, U8G_PI_CS, LOW); + + spiBegin(); + u8g->pin_list[U8G_PI_A0_STATE] = 0; + break; + + case U8G_COM_MSG_ADDRESS: // define cmd (arg_val = 0) or data mode (arg_val = 1) + u8g_SetPILevel(u8g, U8G_PI_A0, arg_val); + u8g->pin_list[U8G_PI_A0_STATE] = arg_val; + break; + + case U8G_COM_MSG_CHIP_SELECT: // arg_val == 1 means chip selected, but ST7920 is active high, so needs inverting + u8g_SetPILevel(u8g, U8G_PI_CS, arg_val ? HIGH : LOW); + break; + + case U8G_COM_MSG_RESET: + u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); + break; + + case U8G_COM_MSG_WRITE_BYTE: + spiBeginTransaction(LCD_SPI_SPEED, MSBFIRST, SPI_MODE0); + + if (u8g->pin_list[U8G_PI_A0_STATE] == 0) { // command + SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2; + } + else if (u8g->pin_list[U8G_PI_A0_STATE] == 1) { // data + SPI.transfer(0x0fa); u8g->pin_list[U8G_PI_A0_STATE] = 2; + } + + SPI.transfer(arg_val & 0x0f0); + SPI.transfer(arg_val << 4); + SPI.endTransaction(); + break; + + case U8G_COM_MSG_WRITE_SEQ: + spiBeginTransaction(LCD_SPI_SPEED, MSBFIRST, SPI_MODE0); + + if (u8g->pin_list[U8G_PI_A0_STATE] == 0 ) { // command + SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2; + } + else if (u8g->pin_list[U8G_PI_A0_STATE] == 1) { // data + SPI.transfer(0x0fa); u8g->pin_list[U8G_PI_A0_STATE] = 2; + } + + uint8_t *ptr = (uint8_t*)arg_ptr; + while (arg_val > 0) { + SPI.transfer((*ptr) & 0x0f0); + SPI.transfer((*ptr) << 4); + ptr++; + arg_val--; + } + + SPI.endTransaction(); + break; + } + return 1; +} + +#endif // HAS_MARLINUI_U8GLIB + +#endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index bd1c98bfa1..aea908707b 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -18,6 +19,10 @@ * along with this program. If not, see . * */ + +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ #ifdef __SAMD51__ #include "../../inc/MarlinConfig.h" @@ -42,24 +47,28 @@ #endif #endif -#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1) -#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1) -#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1) -#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1) -#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1) -#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1) -#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1) -#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1) -#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1) -#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1) -#define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1) -#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1) -#define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) -#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1) -#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) -#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1) -#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1) -#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1) +#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1) +#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1) +#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1) +#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1) +#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1) +#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1) +#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1) +#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1) +#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1) +#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1) +#define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1) +#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1) +#define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) +#define GET_SOC_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) +#define GET_FILAMENT_WIDTH_ADC() TERN(HAS_FILWIDTH_ADC, PIN_TO_ADC(FILWIDTH_PIN), -1) +#define GET_FILAMENT2_WIDTH_ADC() TERN(HAS_FILWIDTH2_ADC, PIN_TO_ADC(FILWIDTH2_PIN), -1) +#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) +#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1) +#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1) +#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1) +#define GET_POWERMON_ADC_CURRENT() TERN(POWER_MONITOR_CURRENT, PIN_TO_ADC(POWER_MONITOR_CURRENT_PIN), -1) +#define GET_POWERMON_ADC_VOLTS() TERN(POWER_MONITOR_VOLTAGE, PIN_TO_ADC(POWER_MONITOR_VOLTAGE_PIN), -1) #define IS_ADC_REQUIRED(n) ( \ GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \ @@ -68,10 +77,11 @@ || GET_CHAMBER_ADC() == n \ || GET_PROBE_ADC() == n \ || GET_COOLER_ADC() == n \ - || GET_BOARD_ADC() == n \ - || GET_FILAMENT_WIDTH_ADC() == n \ + || GET_BOARD_ADC() == n || GET_SOC_ADC() == n \ + || GET_FILAMENT_WIDTH_ADC() == n || GET_FILAMENT2_WIDTH_ADC() == n \ || GET_BUTTONS_ADC() == n \ || GET_JOY_ADC_X() == n || GET_JOY_ADC_Y() == n || GET_JOY_ADC_Z() == n \ + || GET_POWERMON_ADC_CURRENT() == n || GET_POWERMON_ADC_VOLTS() == n \ ) #if IS_ADC_REQUIRED(0) @@ -131,9 +141,15 @@ enum ADCIndex { #if GET_BOARD_ADC() == 0 TEMP_BOARD, #endif + #if GET_SOC_ADC() == 0 + TEMP_SOC, + #endif #if GET_FILAMENT_WIDTH_ADC() == 0 FILWIDTH, #endif + #if GET_FILAMENT2_WIDTH_ADC() == 0 + FILWIDTH2, + #endif #if GET_BUTTONS_ADC() == 0 ADC_KEY, #endif @@ -146,6 +162,15 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 JOY_Z, #endif + #if GET_POWERMON_ADC_CURRENT() == 0 + POWERMON_CURRENT, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + POWERMON_VOLTAGE, + #endif + + // Indexes for ADC1 after those for ADC0 + #if GET_TEMP_0_ADC() == 1 TEMP_0, #endif @@ -185,9 +210,15 @@ enum ADCIndex { #if GET_BOARD_ADC() == 1 TEMP_BOARD, #endif + #if GET_SOC_ADC() == 1 + TEMP_SOC, + #endif #if GET_FILAMENT_WIDTH_ADC() == 1 FILWIDTH, #endif + #if GET_FILAMENT2_WIDTH_ADC() == 1 + FILWIDTH2, + #endif #if GET_BUTTONS_ADC() == 1 ADC_KEY, #endif @@ -200,6 +231,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 JOY_Z, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + POWERMON_CURRENT, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + POWERMON_VOLTAGE, + #endif ADC_COUNT }; @@ -298,9 +335,15 @@ enum ADCIndex { #if GET_BOARD_ADC() == 0 TEMP_BOARD_PIN, #endif + #if GET_SOC_ADC() == 0 + TEMP_SOC_PIN, + #endif #if GET_FILAMENT_WIDTH_ADC() == 0 FILWIDTH_PIN, #endif + #if GET_FILAMENT2_WIDTH_ADC() == 0 + FILWIDTH2_PIN, + #endif #if GET_BUTTONS_ADC() == 0 ADC_KEYPAD_PIN, #endif @@ -313,7 +356,15 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 JOY_Z_PIN, #endif - // ADC1 pins + #if GET_POWERMON_ADC_CURRENT() == 0 + POWER_MONITOR_CURRENT_PIN, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + POWER_MONITOR_VOLTAGE_PIN, + #endif + + // Pins for ADC1 after ADC0 + #if GET_TEMP_0_ADC() == 1 TEMP_0_PIN, #endif @@ -353,9 +404,15 @@ enum ADCIndex { #if GET_BOARD_ADC() == 1 TEMP_BOARD_PIN, #endif + #if GET_SOC_ADC() == 1 + TEMP_SOC_PIN, + #endif #if GET_FILAMENT_WIDTH_ADC() == 1 FILWIDTH_PIN, #endif + #if GET_FILAMENT2_WIDTH_ADC() == 1 + FILWIDTH2_PIN, + #endif #if GET_BUTTONS_ADC() == 1 ADC_KEYPAD_PIN, #endif @@ -368,6 +425,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 JOY_Z_PIN, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + POWER_MONITOR_CURRENT_PIN, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + POWER_MONITOR_VOLTAGE_PIN, + #endif }; static uint16_t adc_results[ADC_COUNT]; @@ -415,9 +478,15 @@ enum ADCIndex { #if GET_BOARD_ADC() == 0 { PIN_TO_INPUTCTRL(TEMP_BOARD_PIN) }, #endif + #if GET_SOC_ADC() == 0 + { PIN_TO_INPUTCTRL(TEMP_SOC_PIN) }, + #endif #if GET_FILAMENT_WIDTH_ADC() == 0 { PIN_TO_INPUTCTRL(FILWIDTH_PIN) }, #endif + #if GET_FILAMENT2_WIDTH_ADC() == 0 + { PIN_TO_INPUTCTRL(FILWIDTH2_PIN) }, + #endif #if GET_BUTTONS_ADC() == 0 { PIN_TO_INPUTCTRL(ADC_KEYPAD_PIN) }, #endif @@ -430,6 +499,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 { PIN_TO_INPUTCTRL(JOY_Z_PIN) }, #endif + #if GET_POWERMON_ADC_CURRENT() == 0 + { PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) }, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTAGE_PIN) }, + #endif }; #define ADC0_AINCOUNT COUNT(adc0_dma_regs_list) @@ -478,9 +553,15 @@ enum ADCIndex { #if GET_BOARD_ADC() == 1 { PIN_TO_INPUTCTRL(TEMP_BOARD_PIN) }, #endif + #if GET_SOC_ADC() == 1 + { PIN_TO_INPUTCTRL(TEMP_SOC_PIN) }, + #endif #if GET_FILAMENT_WIDTH_ADC() == 1 { PIN_TO_INPUTCTRL(FILWIDTH_PIN) }, #endif + #if GET_FILAMENT2_WIDTH_ADC() == 1 + { PIN_TO_INPUTCTRL(FILWIDTH2_PIN) }, + #endif #if GET_BUTTONS_ADC() == 1 { PIN_TO_INPUTCTRL(ADC_KEYPAD_PIN) }, #endif @@ -493,6 +574,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 { PIN_TO_INPUTCTRL(JOY_Z_PIN) }, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + { PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) }, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTAGE_PIN) }, + #endif }; #define ADC1_AINCOUNT COUNT(adc1_dma_regs_list) @@ -597,11 +684,11 @@ void MarlinHAL::dma_init() { // HAL initialization task void MarlinHAL::init() { TERN_(DMA_IS_REQUIRED, dma_init()); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #if HAS_SD_DETECT && SD_CONNECTION_IS(ONBOARD) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif - OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up + OUT_WRITE(SD_SS_PIN, HIGH); // Try to set SDSS inactive before any other SPI users start up #endif } @@ -645,10 +732,10 @@ void MarlinHAL::adc_init() { #if ADC_IS_REQUIRED memset(adc_results, 0xFF, sizeof(adc_results)); // Fill result with invalid values - LOOP_L_N(pi, COUNT(adc_pins)) + for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi) pinPeripheral(adc_pins[pi], PIO_ANALOG); - LOOP_S_LE_N(ai, FIRST_ADC, LAST_ADC) { + for (uint8_t ai = FIRST_ADC; ai <= LAST_ADC; ++ai) { Adc* adc = ((Adc*[])ADC_INSTS)[ai]; // ADC clock setup @@ -680,7 +767,7 @@ void MarlinHAL::adc_init() { void MarlinHAL::adc_start(const pin_t pin) { #if ADC_IS_REQUIRED - LOOP_L_N(pi, COUNT(adc_pins)) + for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi) if (pin == adc_pins[pi]) { adc_result = adc_results[pi]; return; } #endif diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 79ba8021f4..65dcce966d 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,6 +21,10 @@ */ #pragma once +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + #define CPU_32_BIT #include "../shared/Marduino.h" @@ -29,62 +34,7 @@ #ifdef ADAFRUIT_GRAND_CENTRAL_M4 #include "MarlinSerial_AGCM4.h" - - // Serial ports - typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; - typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; - typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; - typedef ForwardSerial1Class< decltype(Serial3) > DefaultSerial4; - typedef ForwardSerial1Class< decltype(Serial4) > DefaultSerial5; - extern DefaultSerial1 MSerial0; - extern DefaultSerial2 MSerial1; - extern DefaultSerial3 MSerial2; - extern DefaultSerial4 MSerial3; - extern DefaultSerial5 MSerial4; - - #define __MSERIAL(X) MSerial##X - #define _MSERIAL(X) __MSERIAL(X) - #define MSERIAL(X) _MSERIAL(INCREMENT(X)) - - #if SERIAL_PORT == -1 - #define MYSERIAL1 MSerial0 - #elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL1 MSERIAL(SERIAL_PORT) - #else - #error "SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." - #endif - - #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == -1 - #define MYSERIAL2 MSerial0 - #elif WITHIN(SERIAL_PORT_2, 0, 3) - #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) - #else - #error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB." - #endif - #endif - - #ifdef MMU2_SERIAL_PORT - #if MMU2_SERIAL_PORT == -1 - #define MMU2_SERIAL MSerial0 - #elif WITHIN(MMU2_SERIAL_PORT, 0, 3) - #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) - #else - #error "MMU2_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." - #endif - #endif - - #ifdef LCD_SERIAL_PORT - #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL MSerial0 - #elif WITHIN(LCD_SERIAL_PORT, 0, 3) - #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) - #else - #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." - #endif - #endif - -#endif // ADAFRUIT_GRAND_CENTRAL_M4 +#endif typedef int8_t pin_t; @@ -107,7 +57,7 @@ typedef Servo hal_servo_t; // //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 // ... 12 // @@ -171,7 +121,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index 77f4d5ecd5..63d3971965 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -19,6 +20,10 @@ * */ +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + /** * Hardware and software SPI implementations are included in this file. * @@ -39,7 +44,7 @@ // Public functions // -------------------------------------------------------------------------- -#if EITHER(SOFTWARE_SPI, FORCE_SOFT_SPI) +#if ANY(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp index a16ea2f758..baa7a38503 100644 --- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp +++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -18,6 +19,10 @@ * along with this program. If not, see . * */ + +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ #ifdef ADAFRUIT_GRAND_CENTRAL_M4 /** diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h index ac5a379398..7827c1f958 100644 --- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h +++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,6 +21,10 @@ */ #pragma once +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + #include "../../core/serial_hook.h" typedef Serial1Class UartT; @@ -27,3 +32,24 @@ typedef Serial1Class UartT; extern UartT Serial2; extern UartT Serial3; extern UartT Serial4; + +typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; +typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; +typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; +typedef ForwardSerial1Class< decltype(Serial3) > DefaultSerial4; +typedef ForwardSerial1Class< decltype(Serial4) > DefaultSerial5; + +extern DefaultSerial1 MSerial0; +extern DefaultSerial2 MSerial1; +extern DefaultSerial3 MSerial2; +extern DefaultSerial4 MSerial3; +extern DefaultSerial5 MSerial4; + +#define __MSERIAL(X) MSerial##X +#define _MSERIAL(X) __MSERIAL(X) +#define MSERIAL(X) _MSERIAL(INCREMENT(X)) + +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 3 +#define USB_SERIAL_PORT(...) MSerial0 +#include "../shared/serial_ports.h" diff --git a/Marlin/src/HAL/SAMD51/SAMD51.h b/Marlin/src/HAL/SAMD51/SAMD51.h index 783956140d..8cc19d7155 100644 --- a/Marlin/src/HAL/SAMD51/SAMD51.h +++ b/Marlin/src/HAL/SAMD51/SAMD51.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,6 +21,10 @@ */ #pragma once +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + #define SYNC(sc) while (sc) { \ asm(""); \ } diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp index 665322fe24..059955e11a 100644 --- a/Marlin/src/HAL/SAMD51/Servo.cpp +++ b/Marlin/src/HAL/SAMD51/Servo.cpp @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -19,6 +20,10 @@ * */ +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + /** * This comes from Arduino library which at the moment is buggy and uncompilable */ @@ -49,7 +54,6 @@ #define TIMER_TCCHANNEL(t) ((t) & 1) #define TC_COUNTER_START_VAL 0xFFFF - static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval) FORCE_INLINE static uint16_t getTimerCount() { diff --git a/Marlin/src/HAL/SAMD51/ServoTimers.h b/Marlin/src/HAL/SAMD51/ServoTimers.h index 948d515356..47e0a190aa 100644 --- a/Marlin/src/HAL/SAMD51/ServoTimers.h +++ b/Marlin/src/HAL/SAMD51/ServoTimers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,6 +21,10 @@ */ #pragma once +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + #define _useTimer1 #define _useTimer2 diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp b/Marlin/src/HAL/SAMD51/eeprom/QSPIFlash.cpp similarity index 98% rename from Marlin/src/HAL/SAMD51/QSPIFlash.cpp rename to Marlin/src/HAL/SAMD51/eeprom/QSPIFlash.cpp index fc21a1ad8c..191da1f30c 100644 --- a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom/QSPIFlash.cpp @@ -20,7 +20,7 @@ * */ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(QSPI_EEPROM) diff --git a/Marlin/src/HAL/SAMD51/eeprom/QSPIFlash.h b/Marlin/src/HAL/SAMD51/eeprom/QSPIFlash.h new file mode 100644 index 0000000000..58822fe05f --- /dev/null +++ b/Marlin/src/HAL/SAMD51/eeprom/QSPIFlash.h @@ -0,0 +1,49 @@ +/** + * @file QSPIFlash.h + * + * The MIT License (MIT) + * + * Copyright (c) 2019 Ha Thach and Dean Miller for Adafruit Industries LLC + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * Derived from Adafruit_SPIFlash class with no SdFat references + */ +#pragma once + +#include + +// This class extends Adafruit_SPIFlashBase by adding caching support. +// +// This class will use 4096 Bytes of RAM as a block cache. +class QSPIFlash { + public: + static void begin(); + static size_t size(); + static uint8_t readByte(const uint32_t address); + static void writeByte(const uint32_t address, const uint8_t v); + static void flush(); + + private: + static Adafruit_SPIFlashBase * _flashBase; + static uint8_t _buf[SFLASH_SECTOR_SIZE]; + static uint32_t _addr; +}; + +extern QSPIFlash qspi; diff --git a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp b/Marlin/src/HAL/SAMD51/eeprom/eeprom_flash.cpp similarity index 95% rename from Marlin/src/HAL/SAMD51/eeprom_flash.cpp rename to Marlin/src/HAL/SAMD51/eeprom/eeprom_flash.cpp index 871bf22b7f..2387a0f99e 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom/eeprom_flash.cpp @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -18,13 +19,17 @@ * along with this program. If not, see . * */ + +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ #ifdef __SAMD51__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(FLASH_EEPROM_EMULATION) -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_api.h" #define NVMCTRL_CMD(c) do{ \ SYNC(!NVMCTRL->STATUS.bit.READY); \ diff --git a/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp b/Marlin/src/HAL/SAMD51/eeprom/eeprom_qspi.cpp similarity index 81% rename from Marlin/src/HAL/SAMD51/eeprom_qspi.cpp rename to Marlin/src/HAL/SAMD51/eeprom/eeprom_qspi.cpp index faa7637197..e829c28e26 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom/eeprom_qspi.cpp @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -18,19 +19,23 @@ * along with this program. If not, see . * */ + +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ #ifdef __SAMD51__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(QSPI_EEPROM) -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_api.h" #include "QSPIFlash.h" static bool initialized; -size_t PersistentStore::capacity() { return qspi.size(); } +size_t PersistentStore::capacity() { return qspi.size() - eeprom_exclude_size; } bool PersistentStore::access_start() { if (!initialized) { @@ -48,7 +53,7 @@ bool PersistentStore::access_finish() { bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { const uint8_t v = *value; - qspi.writeByte(pos, v); + qspi.writeByte(REAL_EEPROM_ADDR(pos), v); crc16(crc, &v, 1); pos++; value++; @@ -58,7 +63,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { while (size--) { - uint8_t c = qspi.readByte(pos); + const uint8_t c = qspi.readByte(REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp b/Marlin/src/HAL/SAMD51/eeprom/eeprom_wired.cpp similarity index 85% rename from Marlin/src/HAL/SAMD51/eeprom_wired.cpp rename to Marlin/src/HAL/SAMD51/eeprom/eeprom_wired.cpp index 3481fe539c..fc1eb09a0c 100644 --- a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp +++ b/Marlin/src/HAL/SAMD51/eeprom/eeprom_wired.cpp @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -18,9 +19,13 @@ * along with this program. If not, see . * */ + +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ #ifdef __SAMD51__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if USE_WIRED_EEPROM @@ -29,13 +34,13 @@ * with simple implementations supplied by Marlin. */ -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" #ifndef MARLIN_EEPROM_SIZE #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } @@ -44,7 +49,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui uint16_t written = 0; while (size--) { const uint8_t v = *value; - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes @@ -62,7 +67,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { while (size--) { - uint8_t c = eeprom_read_byte((uint8_t*)pos); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h index 2f02f404f5..4e342f754f 100644 --- a/Marlin/src/HAL/SAMD51/endstop_interrupts.h +++ b/Marlin/src/HAL/SAMD51/endstop_interrupts.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,13 +21,17 @@ */ #pragma once +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + /** * Endstop interrupts for ATMEL SAMD51 based targets. * * On SAMD51, all pins support external interrupt capability. * Any pin can be used for external interrupts, but there are some restrictions. * At most 16 different external interrupts can be used at one time. - * Further, you can’t just pick any 16 pins to use. This is because every pin on the SAMD51 + * Further, you can't just pick any 16 pins to use. This is because every pin on the SAMD51 * connects to what is called an EXTINT line, and only one pin per EXTINT line can be used for external * interrupts at a time */ @@ -48,31 +53,36 @@ #include "../../module/endstops.h" #define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) -#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) -#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) -#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) -#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) -#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) -#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) -#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) -#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) -#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) -#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) -#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) -#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) -#define MATCH_U_MAX_EILINE(P) TERN0(HAS_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN)) -#define MATCH_U_MIN_EILINE(P) TERN0(HAS_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN)) -#define MATCH_V_MAX_EILINE(P) TERN0(HAS_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN)) -#define MATCH_V_MIN_EILINE(P) TERN0(HAS_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN)) -#define MATCH_W_MAX_EILINE(P) TERN0(HAS_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN)) -#define MATCH_W_MIN_EILINE(P) TERN0(HAS_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN)) -#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) -#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) -#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) -#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) -#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) -#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) -#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) +#define MATCH_X_MAX_EILINE(P) TERN0(USE_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) +#define MATCH_X_MIN_EILINE(P) TERN0(USE_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) +#define MATCH_Y_MAX_EILINE(P) TERN0(USE_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) +#define MATCH_Y_MIN_EILINE(P) TERN0(USE_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) +#define MATCH_Z_MAX_EILINE(P) TERN0(USE_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) +#define MATCH_Z_MIN_EILINE(P) TERN0(USE_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) +#define MATCH_I_MAX_EILINE(P) TERN0(USE_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) +#define MATCH_I_MIN_EILINE(P) TERN0(USE_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) +#define MATCH_J_MAX_EILINE(P) TERN0(USE_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) +#define MATCH_J_MIN_EILINE(P) TERN0(USE_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) +#define MATCH_K_MAX_EILINE(P) TERN0(USE_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) +#define MATCH_K_MIN_EILINE(P) TERN0(USE_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) +#define MATCH_U_MAX_EILINE(P) TERN0(USE_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN)) +#define MATCH_U_MIN_EILINE(P) TERN0(USE_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN)) +#define MATCH_V_MAX_EILINE(P) TERN0(USE_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN)) +#define MATCH_V_MIN_EILINE(P) TERN0(USE_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN)) +#define MATCH_W_MAX_EILINE(P) TERN0(USE_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN)) +#define MATCH_W_MIN_EILINE(P) TERN0(USE_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN)) +#define MATCH_X2_MAX_EILINE(P) TERN0(USE_X2_MAX, DEFER4(MATCH_EILINE)(P, X2_MAX_PIN)) +#define MATCH_X2_MIN_EILINE(P) TERN0(USE_X2_MIN, DEFER4(MATCH_EILINE)(P, X2_MIN_PIN)) +#define MATCH_Y2_MAX_EILINE(P) TERN0(USE_Y2_MAX, DEFER4(MATCH_EILINE)(P, Y2_MAX_PIN)) +#define MATCH_Y2_MIN_EILINE(P) TERN0(USE_Y2_MIN, DEFER4(MATCH_EILINE)(P, Y2_MIN_PIN)) +#define MATCH_Z2_MAX_EILINE(P) TERN0(USE_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) +#define MATCH_Z2_MIN_EILINE(P) TERN0(USE_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) +#define MATCH_Z3_MAX_EILINE(P) TERN0(USE_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) +#define MATCH_Z3_MIN_EILINE(P) TERN0(USE_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) +#define MATCH_Z4_MAX_EILINE(P) TERN0(USE_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) +#define MATCH_Z4_MIN_EILINE(P) TERN0(USE_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) +#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(USE_Z_MIN_PROBE, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) +#define MATCH_CALIBRATION_EILINE(P) TERN0(USE_CALIBRATION, DEFER4(MATCH_EILINE)(P, CALIBRATION_PIN)) #define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \ && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ @@ -84,163 +94,172 @@ && !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P) \ && !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P) \ && !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P) \ + && !MATCH_X2_MAX_EILINE(P) && !MATCH_X2_MIN_EILINE(P) \ + && !MATCH_Y2_MAX_EILINE(P) && !MATCH_Y2_MIN_EILINE(P) \ && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ - && !MATCH_Z_MIN_PROBE_EILINE(P) ) + && !MATCH_Z_MIN_PROBE_EILINE(P) \ + && !MATCH_CALIBRATION_EILINE(P) ) // One ISR for all EXT-Interrupts void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) - #if HAS_X_MAX + #if USE_X_MAX #if !AVAILABLE_EILINE(X_MAX_PIN) - #error "X_MAX_PIN has no EXTINT line available." + #error "X_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MAX_PIN); #endif - #if HAS_X_MIN + #if USE_X_MIN #if !AVAILABLE_EILINE(X_MIN_PIN) - #error "X_MIN_PIN has no EXTINT line available." + #error "X_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MIN_PIN); #endif - #if HAS_Y_MAX + #if USE_Y_MAX #if !AVAILABLE_EILINE(Y_MAX_PIN) - #error "Y_MAX_PIN has no EXTINT line available." + #error "Y_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MAX_PIN); #endif - #if HAS_Y_MIN + #if USE_Y_MIN #if !AVAILABLE_EILINE(Y_MIN_PIN) - #error "Y_MIN_PIN has no EXTINT line available." + #error "Y_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MIN_PIN); #endif - #if HAS_Z_MAX + #if USE_Z_MAX #if !AVAILABLE_EILINE(Z_MAX_PIN) - #error "Z_MAX_PIN has no EXTINT line available." + #error "Z_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MAX_PIN); #endif - #if HAS_Z_MIN + #if USE_Z_MIN #if !AVAILABLE_EILINE(Z_MIN_PIN) - #error "Z_MIN_PIN has no EXTINT line available." + #error "Z_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PIN); #endif - #if HAS_Z2_MAX + #if USE_Z2_MAX #if !AVAILABLE_EILINE(Z2_MAX_PIN) - #error "Z2_MAX_PIN has no EXTINT line available." + #error "Z2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MAX_PIN); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN #if !AVAILABLE_EILINE(Z2_MIN_PIN) - #error "Z2_MIN_PIN has no EXTINT line available." + #error "Z2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MIN_PIN); #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX #if !AVAILABLE_EILINE(Z3_MAX_PIN) - #error "Z3_MAX_PIN has no EXTINT line available." + #error "Z3_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MAX_PIN); #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN #if !AVAILABLE_EILINE(Z3_MIN_PIN) - #error "Z3_MIN_PIN has no EXTINT line available." + #error "Z3_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MIN_PIN); #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX #if !AVAILABLE_EILINE(Z4_MAX_PIN) - #error "Z4_MAX_PIN has no EXTINT line available." + #error "Z4_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MAX_PIN); #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN #if !AVAILABLE_EILINE(Z4_MIN_PIN) - #error "Z4_MIN_PIN has no EXTINT line available." + #error "Z4_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MIN_PIN); #endif - #if HAS_Z_MIN_PROBE_PIN + #if USE_Z_MIN_PROBE #if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN) - #error "Z_MIN_PROBE_PIN has no EXTINT line available." + #error "Z_MIN_PROBE_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PROBE_PIN); #endif - #if HAS_I_MAX + #if USE_CALIBRATION + #if !AVAILABLE_EILINE(CALIBRATION_PIN) + #error "CALIBRATION_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(CALIBRATION_PIN); + #endif + #if USE_I_MAX #if !AVAILABLE_EILINE(I_MAX_PIN) - #error "I_MAX_PIN has no EXTINT line available." + #error "I_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_I_MIN + #if USE_I_MIN #if !AVAILABLE_EILINE(I_MIN_PIN) - #error "I_MIN_PIN has no EXTINT line available." + #error "I_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_J_MAX + #if USE_J_MAX #if !AVAILABLE_EILINE(J_MAX_PIN) - #error "J_MAX_PIN has no EXTINT line available." + #error "J_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_J_MIN + #if USE_J_MIN #if !AVAILABLE_EILINE(J_MIN_PIN) - #error "J_MIN_PIN has no EXTINT line available." + #error "J_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_K_MAX + #if USE_K_MAX #if !AVAILABLE_EILINE(K_MAX_PIN) - #error "K_MAX_PIN has no EXTINT line available." + #error "K_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_K_MIN + #if USE_K_MIN #if !AVAILABLE_EILINE(K_MIN_PIN) - #error "K_MIN_PIN has no EXTINT line available." + #error "K_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_U_MAX + #if USE_U_MAX #if !AVAILABLE_EILINE(U_MAX_PIN) - #error "U_MAX_PIN has no EXTINT line available." + #error "U_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_U_MIN + #if USE_U_MIN #if !AVAILABLE_EILINE(U_MIN_PIN) - #error "U_MIN_PIN has no EXTINT line available." + #error "U_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_V_MAX + #if USE_V_MAX #if !AVAILABLE_EILINE(V_MAX_PIN) - #error "V_MAX_PIN has no EXTINT line available." + #error "V_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_V_MIN + #if USE_V_MIN #if !AVAILABLE_EILINE(V_MIN_PIN) - #error "V_MIN_PIN has no EXTINT line available." + #error "V_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_W_MAX + #if USE_W_MAX #if !AVAILABLE_EILINE(W_MAX_PIN) - #error "W_MAX_PIN has no EXTINT line available." + #error "W_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_W_MIN + #if USE_W_MIN #if !AVAILABLE_EILINE(W_MIN_PIN) - #error "W_MIN_PIN has no EXTINT line available." + #error "W_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE); #endif diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h index 79aede5790..1a67b6ce20 100644 --- a/Marlin/src/HAL/SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,6 +21,10 @@ */ #pragma once +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + /** * Fast IO functions for SAMD51 */ @@ -125,7 +130,7 @@ #ifdef ADAFRUIT_GRAND_CENTRAL_M4 - /* + /** * Adafruit Grand Central M4 has a lot of PWMs the availables are listed here. * Some of these share the same source and so can't be used in the same time */ @@ -169,9 +174,9 @@ : (P == 17) ? PIN_TO_SAMD_PIN(13) \ : PIN_TO_SAMD_PIN(9)) - #define digitalPinToAnalogInput(P) (WITHIN(P, 67, 74) ? (P) - 67 : WITHIN(P, 54, 61) ? 8 + (P) - 54 : WITHIN(P, 12, 13) ? 16 + (P) - 12 : P == 9 ? 18 : -1) + #define digitalPinToAnalogIndex(P) (WITHIN(P, 67, 74) ? (P) - 67 : WITHIN(P, 54, 61) ? 8 + (P) - 54 : WITHIN(P, 12, 13) ? 16 + (P) - 12 : P == 9 ? 18 : -1) - /* + /** * pins */ diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h index 932348c52f..5f1c4b1601 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h @@ -20,7 +20,3 @@ * */ #pragma once - -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/SAMD51." -#endif diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h index ce6d3fdde2..295596b78b 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h @@ -23,6 +23,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_type.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h index 1b876c947d..4719ac6eb8 100644 --- a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h +++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -18,11 +19,20 @@ * along with this program. If not, see . * */ +#pragma once + +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ /** * Test SAMD51 specific configuration values for errors at compile-time. */ +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for HAL/SAMD51." +#endif + #if ENABLED(FLASH_EEPROM_EMULATION) #warning "Did you activate the SmartEEPROM? See https://github.com/GMagician/SAMD51-SmartEEprom-Manager/releases" #endif @@ -44,12 +54,12 @@ #error "EMERGENCY_PARSER is not yet implemented for SAMD51. Disable EMERGENCY_PARSER to continue." #endif -#if ENABLED(SDIO_SUPPORT) - #error "SDIO_SUPPORT is not supported on SAMD51." +#if ENABLED(ONBOARD_SDIO) + #error "ONBOARD_SDIO is not supported on SAMD51." #endif #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on SAMD51." + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported for HAL/SAMD51." #endif #if ENABLED(POSTMORTEM_DEBUGGING) diff --git a/Marlin/src/HAL/SAMD51/pinsDebug.h b/Marlin/src/HAL/SAMD51/pinsDebug.h index f0a46fd7c5..1518c615c9 100644 --- a/Marlin/src/HAL/SAMD51/pinsDebug.h +++ b/Marlin/src/HAL/SAMD51/pinsDebug.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,38 +21,58 @@ */ #pragma once +/** + * Pins Debugging for SAMD51 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + #define NUMBER_PINS_TOTAL PINS_COUNT -#define digitalRead_mod(p) extDigitalRead(p) -#define PRINT_PORT(p) do{ SERIAL_ECHOPGM(" Port: "); sprintf_P(buffer, PSTR("%c%02ld"), 'A' + g_APinDescription[p].ulPort, g_APinDescription[p].ulPin); SERIAL_ECHO(buffer); }while (0) -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) -#define GET_ARRAY_PIN(p) pin_array[p].pin -#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital -#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL) -#define DIGITAL_PIN_TO_ANALOG_PIN(p) digitalPinToAnalogInput(p) -#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P)!=-1) -#define pwm_status(pin) digitalPinHasPWM(pin) +#define digitalRead_mod(P) extDigitalRead(P) +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define getPinByIndex(x) pin_array[x].pin +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL)) +#define isAnalogPin(P) (digitalPinToAnalogIndex(P) != -1) +#define pwm_status(P) digitalPinHasPWM(P) #define MULTI_NAME_PAD 27 // space needed to be pretty if not first name assigned to a pin // pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities // uses pin index #define M43_NEVER_TOUCH(Q) ((Q) >= 75) -bool GET_PINMODE(int8_t pin) { // 1: output, 0: input +bool getValidPinMode(const int8_t pin) { // 1: output, 0: input const EPortType samdport = g_APinDescription[pin].ulPort; const uint32_t samdpin = g_APinDescription[pin].ulPin; return PORT->Group[samdport].DIR.reg & MASK(samdpin) || (PORT->Group[samdport].PINCFG[samdpin].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN; } -void pwm_details(int32_t pin) { +void printPinPWM(const int32_t pin) { if (pwm_status(pin)) { //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative; //SERIAL_ECHOPGM("PWM = ", duty); } } +void printPinPort(const pin_t) {} + /** * AGCM4 Board pin | PORT | Label * ----------------+--------+------- diff --git a/Marlin/src/HAL/SAMD51/spi_pins.h b/Marlin/src/HAL/SAMD51/spi_pins.h index 2a667bcaa1..a2d5b72ec4 100644 --- a/Marlin/src/HAL/SAMD51/spi_pins.h +++ b/Marlin/src/HAL/SAMD51/spi_pins.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,9 +21,13 @@ */ #pragma once +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + #ifdef ADAFRUIT_GRAND_CENTRAL_M4 - /* + /** * AGCM4 Default SPI Pins * * SS SCK MISO MOSI @@ -41,14 +46,9 @@ #ifndef SD_MOSI_PIN #define SD_MOSI_PIN 51 #endif - #ifndef SDSS - #define SDSS 53 - #endif #else #error "Unsupported board!" #endif - -#define SD_SS_PIN SDSS diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp index 1ad0e36073..7a211eb36a 100644 --- a/Marlin/src/HAL/SAMD51/timers.cpp +++ b/Marlin/src/HAL/SAMD51/timers.cpp @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -18,6 +19,10 @@ * along with this program. If not, see . * */ + +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ #ifdef __SAMD51__ // -------------------------------------------------------------------------- diff --git a/Marlin/src/HAL/SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h index 86e980c566..2682891cdc 100644 --- a/Marlin/src/HAL/SAMD51/timers.h +++ b/Marlin/src/HAL/SAMD51/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,6 +21,10 @@ */ #pragma once +/** + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + */ + #include // -------------------------------------------------------------------------- @@ -27,7 +32,7 @@ // -------------------------------------------------------------------------- typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define HAL_TIMER_RATE F_CPU // frequency of timers peripherals @@ -43,15 +48,14 @@ typedef uint32_t hal_timer_t; #define MF_TIMER_TEMP MF_TIMER_RTC // Timer Index for Temperature #endif -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // (MHz) Stepper Timer ticks per µs #define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) #define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) @@ -140,4 +144,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(timer_num) +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/SAMD51/u8g/LCD_defines.h b/Marlin/src/HAL/SAMD51/u8g/LCD_defines.h new file mode 100644 index 0000000000..658a2c0fc1 --- /dev/null +++ b/Marlin/src/HAL/SAMD51/u8g/LCD_defines.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * SAMD51 LCD-specific defines + */ + +#define U8G_COM_HAL_HW_SPI_FN u8g_com_samd51_hw_spi_fn // See U8glib-HAL +#define U8G_COM_ST7920_HAL_HW_SPI u8g_com_samd51_st7920_hw_spi_fn // See U8glib-HAL diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index aff52f597f..018fb48881 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -44,8 +43,8 @@ #endif #if HAS_SD_HOST_DRIVE - #include "msc_sd.h" - #include "usbd_cdc_if.h" + #include "sd/msc_sd.h" + #include #endif // ------------------------ @@ -67,11 +66,11 @@ void MarlinHAL::init() { // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. - constexpr int cpuFreq = F_CPU; + constexpr unsigned int cpuFreq = F_CPU; UNUSED(cpuFreq); - #if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT) && (defined(SDSS) && SDSS != -1) - OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up + #if HAS_MEDIA && DISABLED(ONBOARD_SDIO) && PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); // Try to set SDSS inactive before any other SPI users start up #endif #if PIN_EXISTS(LED) @@ -88,7 +87,7 @@ void MarlinHAL::init() { SetTimerInterruptPriorities(); - #if ENABLED(EMERGENCY_PARSER) && (USBD_USE_CDC || USBD_USE_CDC_MSC) + #if ENABLED(EMERGENCY_PARSER) && ANY(USBD_USE_CDC, USBD_USE_CDC_MSC) USB_Hook_init(); #endif @@ -98,7 +97,7 @@ void MarlinHAL::init() { #if PIN_EXISTS(USB_CONNECT) OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection - delay(1000); // Give OS time to notice + delay_ms(1000); // Give OS time to notice WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); #endif } @@ -115,7 +114,7 @@ void MarlinHAL::idletask() { void MarlinHAL::reboot() { NVIC_SystemReset(); } uint8_t MarlinHAL::get_reset_source() { - return + return ( #ifdef RCC_FLAG_IWDGRST // Some sources may not exist... RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG : #endif @@ -135,7 +134,7 @@ uint8_t MarlinHAL::get_reset_source() { RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) ? RST_POWER_ON : #endif 0 - ; + ); } void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 3e85aca293..24889c872a 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -24,17 +23,13 @@ #define CPU_32_BIT -#include "../../core/macros.h" -#include "../shared/Marduino.h" -#include "../shared/math_32bit.h" -#include "../shared/HAL_SPI.h" -#include "fastio.h" -#include "Servo.h" -#include "MarlinSerial.h" - #include "../../inc/MarlinConfigPre.h" -#include +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "temp_soc.h" +#include "fastio.h" +#include "Servo.h" // // Default graphical display delays @@ -43,85 +38,17 @@ #define CPU_ST7920_DELAY_2 40 #define CPU_ST7920_DELAY_3 340 -// ------------------------ -// Serial ports -// ------------------------ -#ifdef USBCON - #include - #include "../../core/serial_hook.h" - typedef ForwardSerial1Class< decltype(SerialUSB) > DefaultSerial1; - extern DefaultSerial1 MSerialUSB; -#endif +// +// Serial Ports +// -#define _MSERIAL(X) MSerial##X -#define MSERIAL(X) _MSERIAL(X) - -#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, or -1 for Native USB." -#endif - -#ifdef SERIAL_PORT_2 - #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, or -1 for Native USB." - #endif -#endif - -#ifdef SERIAL_PORT_3 - #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, or -1 for Native USB." - #endif -#endif - -#ifdef MMU2_SERIAL_PORT - #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, or -1 for Native USB." - #endif -#endif - -#ifdef LCD_SERIAL_PORT - #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, or -1 for Native USB." - #endif - #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() - #endif -#endif +#include "MarlinSerial.h" /** * TODO: review this to return 1 for pins that are not analog input */ #ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) (p) + #define analogInputToDigitalPin(p) pin_t(p) #endif // @@ -136,13 +63,7 @@ // Types // ------------------------ -typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs. - -#ifdef STM32G0B1xx - typedef int32_t pin_t; -#else - typedef int16_t pin_t; -#endif +typedef int32_t pin_t; // Parity with platform/ststm32 class libServo; typedef libServo hal_servo_t; @@ -159,7 +80,7 @@ typedef libServo hal_servo_t; #define HAL_ADC_RESOLUTION 12 #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 // // Pin Mapping for M42, M43, M226 @@ -174,7 +95,9 @@ typedef libServo hal_servo_t; #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG #endif -#define PLATFORM_M997_SUPPORT +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif void flashFirmware(const int16_t); // Maple Compatibility @@ -232,7 +155,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 40d320d5e8..b220ae6a78 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -38,7 +37,7 @@ static SPISettings spiConfig; // Public functions // ------------------------ -#if ENABLED(SOFTWARE_SPI) +#if ANY(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI @@ -78,7 +77,6 @@ static SPISettings spiConfig; case SPI_SPEED_6: delaySPIFunc = &delaySPI_2000; break; // desired: 250,000 actual: ~210K default: delaySPIFunc = &delaySPI_4000; break; // desired: 125,000 actual: ~123K } - SPI.begin(); } // Begin SPI transaction, set clock, bit order, data mode diff --git a/Marlin/src/HAL/STM32/HardwareSerial.cpp b/Marlin/src/HAL/STM32/HardwareSerial.cpp new file mode 100644 index 0000000000..58360cc31e --- /dev/null +++ b/Marlin/src/HAL/STM32/HardwareSerial.cpp @@ -0,0 +1,529 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * Copyright (c) 2017 Victor Perez + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +// +// HAL_HardwareSerial Class. Adapted from Arduino HardwareSerial. +// + +#include "../platforms.h" + +#ifdef HAL_STM32 + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(SERIAL_DMA) && defined(HAL_UART_MODULE_ENABLED) && !defined(HAL_UART_MODULE_ONLY) + +#include +#include "HardwareSerial.h" +#include "uart.h" + +// Prevent selection of LPUART1 on STM32H7xx +#if defined(STM32H7xx) && (PIN_SERIAL1_TX == PA_9) + #undef PIN_SERIAL1_TX + #define PIN_SERIAL1_TX PA_9_ALT1 +#endif +#if defined(STM32H7xx) && (PIN_SERIAL1_RX == PA_10) + #undef PIN_SERIAL1_RX + #define PIN_SERIAL1_RX PA_10_ALT1 +#endif + +// USART/UART pin mapping for STM32F0/F1/F2/F4/F7/H7 +#ifndef PIN_SERIAL1_TX + #define PIN_SERIAL1_TX PA9 +#endif +#ifndef PIN_SERIAL1_RX + #define PIN_SERIAL1_RX PA10 +#endif +#ifndef PIN_SERIAL2_TX + #define PIN_SERIAL2_TX PA2 +#endif +#ifndef PIN_SERIAL2_RX + #define PIN_SERIAL2_RX PA3 +#endif +#ifndef PIN_SERIAL3_TX + #define PIN_SERIAL3_TX PB10 +#endif +#ifndef PIN_SERIAL3_RX + #define PIN_SERIAL3_RX PB11 +#endif +#ifndef PIN_SERIAL4_TX + #define PIN_SERIAL4_TX PC10 +#endif +#ifndef PIN_SERIAL4_RX + #define PIN_SERIAL4_RX PC11 +#endif +#ifndef PIN_SERIAL5_TX + #define PIN_SERIAL5_TX PC12 +#endif +#ifndef PIN_SERIAL5_RX + #define PIN_SERIAL5_RX PD2 +#endif +#ifndef PIN_SERIAL6_TX + #define PIN_SERIAL6_TX PC6 +#endif +#ifndef PIN_SERIAL6_RX + #define PIN_SERIAL6_RX PC7 +#endif + +// SerialEvent functions are weak, so when the user doesn't define them, +// the linker just sets their address to 0 (which is checked below). +#ifdef USING_HW_SERIAL1 + HAL_HardwareSerial HSerial1(USART1); + void serialEvent1() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL2 + HAL_HardwareSerial HSerial2(USART2); + void serialEvent2() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL3 + HAL_HardwareSerial HSerial3(USART3); + void serialEvent3() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL4 + #ifdef USART4 + HAL_HardwareSerial HSerial4(USART4); + #else + HAL_HardwareSerial HSerial4(UART4); + #endif + void serialEvent4() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL5 + #ifdef USART5 + HAL_HardwareSerial HSerial5(USART5); + #else + HAL_HardwareSerial HSerial5(UART5); + #endif + void serialEvent5() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL6 + #ifdef USART6 + HAL_HardwareSerial HSerial6(USART6); + #else + HAL_HardwareSerial HSerial6(UART6); + #endif + void serialEvent6() __attribute__((weak)); +#endif + +// Constructors //////////////////////////////////////////////////////////////// + +HAL_HardwareSerial::HAL_HardwareSerial(void *peripheral) { + if (peripheral == USART1) { + setRx(PIN_SERIAL1_RX); + setTx(PIN_SERIAL1_TX); + _uart_index = 0; + + #ifdef DMA2_Stream2 // F2 / F4 / F7 / H7 + RX_DMA = { USART1, 2, DMA2_Stream2 }; // USART, DMA controller no., DMA stream + #endif + #ifdef DMA1_Channel5 // F0 / F1 + RX_DMA = { USART1, 1, DMA1_Channel5 }; // USART, DMA controller no., DMA channel + #endif + } + else if (peripheral == USART2) { + setRx(PIN_SERIAL2_RX); + setTx(PIN_SERIAL2_TX); + _uart_index = 1; + #ifdef DMA1_Stream5 + RX_DMA = { USART2, 1, DMA1_Stream5 }; + #endif + #ifdef DMA1_Channel6 + RX_DMA = { USART2, 1, DMA1_Channel6 }; + #endif + } + else if (peripheral == USART3) { + setRx(PIN_SERIAL3_RX); + setTx(PIN_SERIAL3_TX); + _uart_index = 2; + #ifdef DMA1_Stream1 + RX_DMA = { USART3, 1, DMA1_Stream1 }; + #endif + #ifdef DMA1_Channel3 // F0 has no support for UART3, requires system remapping + RX_DMA = { USART3, 1, DMA1_Channel3 }; + #endif + } + + #ifdef USART4 // Only F2 / F4 / F7 + else if (peripheral == USART4) { + #ifdef DMA1_Stream2 + RX_DMA = { USART4, 1, DMA1_Stream2 }; + #endif + setRx(PIN_SERIAL4_RX); + setTx(PIN_SERIAL4_TX); + _uart_index = 3; + } + #endif + + #ifdef UART4 + else if (peripheral == UART4) { + #ifdef DMA1_Stream2 + RX_DMA = { UART4, 1, DMA1_Stream2 }; + #endif + #ifdef DMA2_Channel3 // STM32F0xx has only 3 UARTs + RX_DMA = { UART4, 2, DMA2_Channel3 }; + #endif + setRx(PIN_SERIAL4_RX); + setTx(PIN_SERIAL4_TX); + _uart_index = 3; + } + #endif + + #ifdef UART5 // Only F2 / F4 / F7 / H7 + else if (peripheral == UART5) { + #ifdef DMA1_Stream0 + RX_DMA = { UART5, 1, DMA1_Stream0 }; + #endif + setRx(PIN_SERIAL5_RX); + setTx(PIN_SERIAL5_TX); + _uart_index = 4; + } + #endif + + #ifdef USART6 // Only F2 / F4 / F7 / H7 + else if (peripheral == USART6) { + #ifdef DMA2_Stream1 + RX_DMA = { USART6, 2, DMA2_Stream1 }; + #endif + setRx(PIN_SERIAL6_RX); + setTx(PIN_SERIAL6_TX); + _uart_index = 5; + } + #endif + + else { // else get the pins of the first peripheral occurrence in PinMap + _serial.pin_rx = pinmap_pin(peripheral, PinMap_UART_RX); + _serial.pin_tx = pinmap_pin(peripheral, PinMap_UART_TX); + } + + init(_serial.pin_rx, _serial.pin_tx); +} + +void HAL_HardwareSerial::setRx(uint32_t _rx) { + _serial.pin_rx = digitalPinToPinName(_rx); +} + +void HAL_HardwareSerial::setTx(uint32_t _tx) { + _serial.pin_tx = digitalPinToPinName(_tx); +} + +void HAL_HardwareSerial::init(PinName _rx, PinName _tx) { + _serial.pin_rx = _rx; + _serial.rx_buff = _rx_buffer; + _serial.rx_head = _serial.rx_tail = 0; + + _serial.pin_tx = _tx; + _serial.tx_buff = _tx_buffer; + _serial.tx_head = _serial.tx_tail = 0; +} + +// Actual interrupt handlers ////////////////////////////////////////////////////////////// + +/** + * @brief Read receive byte from uart + * @param obj : pointer to serial_t structure + * @retval last character received + */ + +#if DISABLED(STM32H7xx) + + int HAL_HardwareSerial::_tx_complete_irq(serial_t *obj) { + // If interrupts are enabled, there must be more data in the output buffer. Send the next byte + obj->tx_tail = (obj->tx_tail + 1) % TX_BUFFER_SIZE; + if (obj->tx_head == obj->tx_tail) + return -1; + + return 0; + } + +#else // STM32H7xx, has different uart_attach_tx_callback + + int HAL_HardwareSerial::_tx_complete_irq(serial_t *obj) { + // If interrupts are enabled, there must be more data in the output buffer. Send the next byte + obj->tx_tail = (obj->tx_tail + obj->tx_size) % TX_BUFFER_SIZE; + + if (obj->tx_head != obj->tx_tail) { + size_t remaining_data = (TX_BUFFER_SIZE + obj->tx_head - obj->tx_tail) % TX_BUFFER_SIZE; + obj->tx_size = min(remaining_data, (size_t)(TX_BUFFER_SIZE - obj->tx_tail)); + uart_attach_tx_callback(obj, _tx_complete_irq, obj->tx_size); + return -1; + } + return 0; + } + +#endif + +// Public Methods ////////////////////////////////////////////////////////////// + +void HAL_HardwareSerial::begin(unsigned long baud, uint8_t config) { + uint32_t databits = 0, stopbits = 0, parity = 0; + + _baud = baud; + _config = config; + + // Manage databits + switch (config & 0x07) { + case 0x02: databits = 6; break; + case 0x04: databits = 7; break; + case 0x06: databits = 8; break; + default: databits = 0; break; + } + + if ((config & 0x30) == 0x30) { + parity = UART_PARITY_ODD; + databits++; + } + else if ((config & 0x20) == 0x20) { + parity = UART_PARITY_EVEN; + databits++; + } + else + parity = UART_PARITY_NONE; + + stopbits = (config & 0x08) == 0x08 ? UART_STOPBITS_2 : UART_STOPBITS_1; + + switch (databits) { + #ifdef UART_WORDLENGTH_7B + case 7: databits = UART_WORDLENGTH_7B; break; + #endif + case 8: databits = UART_WORDLENGTH_8B; break; + case 9: databits = UART_WORDLENGTH_9B; break; + default: + case 0: Error_Handler(); break; + } + + uart_init(&_serial, (uint32_t)baud, databits, parity, stopbits); + Serial_DMA_Read_Enable(); // Start the circular DMA serial reading process, no callback needed +} + +void HAL_HardwareSerial::end() { + flush(); // Wait for transmission of outgoing data + uart_deinit(&_serial); + _serial.rx_head = _serial.rx_tail; // Clear any received data +} + +// Update buffer head for DMA progress +void HAL_HardwareSerial::update_rx_head() { + + #if ENABLED(EMERGENCY_PARSER) + static uint32_t flag = 0; + while (flag != _serial.rx_head) { // send all available data to emergency parser immediately + emergency_parser.update(static_cast(this)->emergency_state, _serial.rx_buff[flag]); + flag = (flag + 1) % RX_BUFFER_SIZE; + } + #endif + + #if ANY(STM32F2xx, STM32F4xx, STM32F7xx, STM32H7xx) + _serial.rx_head = RX_BUFFER_SIZE - RX_DMA.dma_streamRX->NDTR; + #endif + + #if ANY(STM32F0xx, STM32F1xx) + _serial.rx_head = RX_BUFFER_SIZE - RX_DMA.dma_channelRX->CNDTR; + #endif + +} + +int HAL_HardwareSerial::available() { + update_rx_head(); + + return ((unsigned int)(RX_BUFFER_SIZE + _serial.rx_head - _serial.rx_tail)) % RX_BUFFER_SIZE; +} + +int HAL_HardwareSerial::peek() { + update_rx_head(); + if (_serial.rx_head == _serial.rx_tail) + return -1; + + return _serial.rx_buff[_serial.rx_tail]; +} + +int HAL_HardwareSerial::read() { + update_rx_head(); + if (_serial.rx_head == _serial.rx_tail) + return -1; // No chars if the head isn't ahead of the tail + + unsigned char c = _serial.rx_buff[_serial.rx_tail]; + _serial.rx_tail = (rx_buffer_index_t)(_serial.rx_tail + 1) % RX_BUFFER_SIZE; + return c; +} + +size_t HAL_HardwareSerial::write(uint8_t c) { // Interrupt based writing + tx_buffer_index_t i = (_serial.tx_head + 1) % TX_BUFFER_SIZE; + + // If the output buffer is full, there's nothing for it other than to + // wait for the interrupt handler to empty it a bit + while (i == _serial.tx_tail) { /* nada */ } // NOP, let the interrupt free up space for us + + _serial.tx_buff[_serial.tx_head] = c; + _serial.tx_head = i; + + #ifdef STM32H7xx // Support STM32H7xx with different uart_attach_tx_callback + if ((!serial_tx_active(&_serial)) && (_serial.tx_head != _serial.tx_tail)) { + size_t remaining_data = (TX_BUFFER_SIZE + _serial.tx_head -_serial.tx_tail) % TX_BUFFER_SIZE; + _serial.tx_size = min(remaining_data, (size_t)(TX_BUFFER_SIZE - _serial.tx_tail)); + uart_attach_tx_callback(&_serial, _tx_complete_irq, _serial.tx_size); + + return -1; + } + #else + if (!serial_tx_active(&_serial)) + uart_attach_tx_callback(&_serial, _tx_complete_irq); // Write next byte, launch interrupt + #endif + + return 1; +} + +void HAL_HardwareSerial::flush() { + while ((_serial.tx_head != _serial.tx_tail)) { /* nada */ } // nop, the interrupt handler will free up space for us +} + +#if ANY(STM32F2xx, STM32F4xx, STM32F7xx, STM32H7xx) + + void HAL_HardwareSerial::Serial_DMA_Read_Enable() { + + if (RX_DMA.DMA_ID == 1) + __HAL_RCC_DMA1_CLK_ENABLE(); // Enable DMA1 clock + else + __HAL_RCC_DMA2_CLK_ENABLE(); // Enable DMA2 clock + + // Reset DMA, wait if needed to complete the running process + RX_DMA.dma_streamRX->CR = 0; // DMA stream clear/disable + while (RX_DMA.dma_streamRX->CR & DMA_SxCR_EN) { /* just wait for DMA to complete */ } + + // UART clear/disable + RX_DMA.uart->CR1 = 0; + + // Configure DMA + #if ANY(STM32F7xx, STM32H7xx) // F7 and H7 use RDR (Receive Data Register) + RX_DMA.dma_streamRX->PAR = (uint32_t)(&RX_DMA.uart->RDR); // DMA stream Peripheral Address Register = USART Data Register + #else + RX_DMA.dma_streamRX->PAR = (uint32_t)(&RX_DMA.uart->DR); // DMA stream Peripheral Address Register = USART Data Register + #endif + + RX_DMA.dma_streamRX->M0AR = (uint32_t)_serial.rx_buff; // DMA stream Memory 0 Adress Register = RX buffer address + RX_DMA.dma_streamRX->NDTR = RX_BUFFER_SIZE; // DMA stream Number of Data Transfer Register + + #if DISABLED(STM32H7xx) // Select channel via CR register + + RX_DMA.dma_streamRX->CR = 4 << DMA_SxCR_CHSEL_Pos; // DMA stream Channel Selection, always use channel 4 + + #else // STM32H7xx, select channel with DMAMUX1, channel DMA1 is channel DMAMUX, channel DMA2 is channel DMAMUX + 8 + + if (RX_DMA.uart == USART1) DMAMUX1_Channel10->CCR |= DMA_REQUEST_USART1_RX; // DMA2, Stream 2 + if (RX_DMA.uart == USART2) DMAMUX1_Channel5->CCR |= DMA_REQUEST_USART2_RX; // DMA1, Stream 5 + if (RX_DMA.uart == USART3) DMAMUX1_Channel1->CCR |= DMA_REQUEST_USART3_RX; // DMA1, Stream 1 + #ifdef UART4 + if (RX_DMA.uart == UART4) DMAMUX1_Channel2->CCR |= DMA_REQUEST_UART4_RX; // DMA1, Stream 2 + #endif + #ifdef USART4 + if (RX_DMA.uart == USART4) DMAMUX1_Channel2->CCR |= DMA_REQUEST_USART4_RX; // DMA1, Stream 2 + #endif + #ifdef UART5 + if (RX_DMA.uart == UART5) DMAMUX1_Channel0->CCR |= DMA_REQUEST_UART5_RX; // DMA1, Stream 0 + #endif + #ifdef USART6 + if (RX_DMA.uart == USART6) DMAMUX1_Channel9->CCR |= DMA_REQUEST_USART6_RX; // DMA2, Stream 1 + #endif + + #endif // !STM32H7xx + + // Configure DMA + //RX_DMA.dma_streamRX->CR |= DMA_MBURST_SINGLE; // DMA stream Memory Burst transfer: single transfer = 0b00 + //RX_DMA.dma_streamRX->CR |= DMA_PBURST_SINGLE; // DMA stream Peripheral Burst transfer: single transfer = 0b00 + + #if ENABLED(STM32H7xx) + RX_DMA.dma_streamRX->CR |= DMA_SxCR_TRBUFF; // DMA stream Transfer handle bufferable (required for UART/USART) + #endif + + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_CT; // DMA stream Current Target (only in double buffer mode) + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_DBM; // DMA stream Double Buffer Mode + //RX_DMA.dma_streamRX->CR |= DMA_PRIORITY_LOW; // DMA stream Priority Level Low = 0b00 + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_PINCOS; // DMA stream Peripheral Increment Offset Size + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_MSIZE; // DMA stream Memory data Size: 8 bit = 0b00 + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_PSIZE; // DMA stream Peripheral data Size: 8 bit = 0b00 + RX_DMA.dma_streamRX->CR |= DMA_SxCR_MINC; // DMA stream Memory Increment enable + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_PINC; // DMA stream Peripheral increment + RX_DMA.dma_streamRX->CR |= DMA_SxCR_CIRC; // DMA stream Circular mode enable + //RX_DMA.dma_streamRX->CR |= DMA_PERIPH_TO_MEMORY; // DMA stream transfer Direction: Peripheral-to-memory = b00 + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_PFCTRL; // DMA stream Peripheral Flow Controller: DMA = 0 + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_TCIE; // DMA stream Transfer Complete Interrupt + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_HTIE; // DMA stream Half Transfer Interrupt + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_TEIE; // DMA stream Transfer Error Interrupt + //RX_DMA.dma_streamRX->CR &= ~DMA_SxCR_DMEIE; // DMA stream Direct Mode Error Interrupt + RX_DMA.dma_streamRX->CR |= DMA_SxCR_EN; // DMA stream Enable + + // Configure UART/USART + RX_DMA.uart->CR3 |= USART_CR3_DMAR; // UART DMA Receiver + RX_DMA.uart->CR1 |= USART_CR1_TE; // UART Transmitter Enable + RX_DMA.uart->CR1 |= USART_CR1_RE; // UART Receiver Enable + RX_DMA.uart->CR1 |= USART_CR1_UE; // UART Enable + } + +#endif // STM32F2xx || STM32F4xx || STM32F7xx || STM32H7xx + +#if ANY(STM32F0xx, STM32F1xx) + + void HAL_HardwareSerial::Serial_DMA_Read_Enable() { + + if (RX_DMA.DMA_ID == 1) + __HAL_RCC_DMA1_CLK_ENABLE(); // enable DMA1 clock + else + __HAL_RCC_DMA2_CLK_ENABLE(); // enable DMA2 clock + + RX_DMA.dma_channelRX->CCR &= ~USART_CR1_UE; // DMA stream clear/disable + while (RX_DMA.dma_channelRX->CCR & DMA_CCR_EN) { /* just wait for DMA to complete */ } + + // Clear/disable UART and DMA + RX_DMA.uart->CR1 = 0; // UART clear CR1, disable DMA + + // Configure DMA + + #ifdef STM32F0xx + RX_DMA.dma_channelRX->CPAR = (uint32_t)(&RX_DMA.uart->RDR); // DMA channel Peripheral Address Register = USART Data Register + #else + RX_DMA.dma_channelRX->CPAR = (uint32_t)(&RX_DMA.uart->DR); // DMA channel Peripheral Address Register = USART Data Register + #endif + + RX_DMA.dma_channelRX->CMAR = (uint32_t)_serial.rx_buff; // DMA channel Memory Address Register + RX_DMA.dma_channelRX->CNDTR = RX_BUFFER_SIZE; // DMA channel Number of Data Transfer Register + //RX_DMA.dma_channelRX->CCR |= (0b00 << DMA_CCR_PL_Pos); // DMA channel Priority Level: Low = 0b00 + //RX_DMA.dma_channelRX->CCR &= ~DMA_CCR_MSIZE; // DMA channel Data Size: 8 bit = 0 + //RX_DMA.dma_channelRX->CCR &= ~DMA_CCR_PSIZE; // DMA channel Peripheral data size: 8 bit = 0 + RX_DMA.dma_channelRX->CCR |= DMA_CCR_MINC; // DMA channel Memory Increment enable + //RX_DMA.dma_channelRX->CCR &= ~DMA_CCR_PINC; // DMA channel Peripheral Increment disable + RX_DMA.dma_channelRX->CCR |= DMA_CCR_CIRC; // DMA channel Circular mode enable + //RX_DMA.dma_channelRX->CCR &= ~DMA_CCR_DIR; // DMA channel Data Transfer direction: 0=Read peripheral, 1=Read memory + //RX_DMA.dma_channelRX->CCR &= ~DMA_CCR_TEIE; // DMA channel Transfer Error Interrupt + //RX_DMA.dma_channelRX->CCR &= ~DMA_CCR_HTIE; // DMA channel Half Transfer Interrupt + //RX_DMA.dma_channelRX->CCR &= ~DMA_CCR_TCIE; // DMA channel Transfer Complete Interrupt + RX_DMA.dma_channelRX->CCR |= DMA_CCR_EN; // DMA channel enable + + // Configure UART/USART + RX_DMA.uart->CR3 |= USART_CR3_DMAR; // UART DMA Receiver enabled + RX_DMA.uart->CR1 |= USART_CR1_TE; // UART Transmitter Enable + RX_DMA.uart->CR1 |= USART_CR1_RE; // UART Receiver Enable + RX_DMA.uart->CR1 |= USART_CR1_UE; // UART Enable + } + +#endif // STM32F0xx || STM32F1xx + +#endif // SERIAL_DMA && HAL_UART_MODULE_ENABLED && !HAL_UART_MODULE_ONLY +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/HardwareSerial.h b/Marlin/src/HAL/STM32/HardwareSerial.h new file mode 100644 index 0000000000..cf97637278 --- /dev/null +++ b/Marlin/src/HAL/STM32/HardwareSerial.h @@ -0,0 +1,83 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * Copyright (c) 2017 Victor Perez + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// +// HAL_HardwareSerial Class. Adapted from Arduino HardwareSerial. +// + +#if RX_BUFFER_SIZE == 0 + #undef RX_BUFFER_SIZE + #define RX_BUFFER_SIZE 128 +#endif + +#if TX_BUFFER_SIZE == 0 + #undef TX_BUFFER_SIZE + #define TX_BUFFER_SIZE 64 +#endif + +typedef struct { + USART_TypeDef * uart; + uint32_t DMA_ID; // DMA1=1; DM2=2; BDMA=3 + #if ANY(STM32F0xx, STM32F1xx) // F0 / F1 + DMA_Channel_TypeDef * dma_channelRX; + #else // F2 / F4 / F7 / H7 + DMA_Stream_TypeDef * dma_streamRX; + #endif +} DMA_CFG; + +class HAL_HardwareSerial : public Stream { + protected: + // Don't put any members after these buffers, since only the first + // 32 bytes of this struct can be accessed quickly using the ldd instruction. + unsigned char _rx_buffer[RX_BUFFER_SIZE]; + unsigned char _tx_buffer[TX_BUFFER_SIZE]; + + serial_t _serial; + + public: + HAL_HardwareSerial(void *peripheral); + void begin(unsigned long, uint8_t); + void end(); + virtual int available(); + virtual int read(); + virtual int peek(); + virtual size_t write(uint8_t); + virtual void flush(); + operator bool() { return true; } + + void setRx(uint32_t _rx); + void setTx(uint32_t _tx); + + static int _tx_complete_irq(serial_t *obj); // Interrupt handler + + private: + uint8_t _uart_index; + bool _rx_enabled; + uint8_t _config; + unsigned long _baud; + void init(PinName _rx, PinName _tx); + void update_rx_head(); + DMA_CFG RX_DMA; + void Serial_DMA_Read_Enable(); +}; diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index 37a8f40fd0..862678373f 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -37,11 +37,28 @@ #ifndef USART5 #define USART5 UART5 #endif +#ifndef USART6 + #define USART6 UART6 +#endif +#ifndef USART7 + #define USART7 UART7 +#endif +#ifndef USART8 + #define USART8 UART8 +#endif +#ifndef USART9 + #define USART9 UART9 +#endif -#define DECLARE_SERIAL_PORT(ser_num) \ - void _rx_complete_irq_ ## ser_num (serial_t * obj); \ - MSerialT MSerial ## ser_num (true, USART ## ser_num, &_rx_complete_irq_ ## ser_num); \ - void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); } +#if ENABLED(SERIAL_DMA) + #define DECLARE_SERIAL_PORT(ser_num) \ + MSerialT MSerial ## ser_num (true, USART ## ser_num); +#else + #define DECLARE_SERIAL_PORT(ser_num) \ + void _rx_complete_irq_ ## ser_num (serial_t * obj); \ + MSerialT MSerial ## ser_num (true, USART ## ser_num, &_rx_complete_irq_ ## ser_num); \ + void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); } +#endif #if USING_HW_SERIAL1 DECLARE_SERIAL_PORT(1) @@ -78,33 +95,38 @@ #endif void MarlinSerial::begin(unsigned long baud, uint8_t config) { - HardwareSerial::begin(baud, config); - // Replace the IRQ callback with the one we have defined - TERN_(EMERGENCY_PARSER, _serial.rx_callback = _rx_callback); + #if ENABLED(SERIAL_DMA) + HAL_HardwareSerial::begin(baud, config); + #else + HardwareSerial::begin(baud, config); + // Replace the IRQ callback with the one we have defined + TERN_(EMERGENCY_PARSER, _serial.rx_callback = _rx_callback); + #endif } -// This function is Copyright (c) 2006 Nicholas Zambetti. -void MarlinSerial::_rx_complete_irq(serial_t *obj) { - // No Parity error, read byte and store it in the buffer if there is room - unsigned char c; +#if DISABLED(SERIAL_DMA) - if (uart_getc(obj, &c) == 0) { + // This function Copyright (c) 2006 Nicholas Zambetti. + void MarlinSerial::_rx_complete_irq(serial_t *obj) { + // No Parity error, read byte and store it in the buffer if there is room + unsigned char c; + if (uart_getc(obj, &c) == 0) { - rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % SERIAL_RX_BUFFER_SIZE; + rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % SERIAL_RX_BUFFER_SIZE; - // if we should be storing the received character into the location - // just before the tail (meaning that the head would advance to the - // current location of the tail), we're about to overflow the buffer - // and so we don't write the character or advance the head. - if (i != obj->rx_tail) { - obj->rx_buff[obj->rx_head] = c; - obj->rx_head = i; + // If tail overlaps head the buffer is overflowed + // so don't write the character or advance the head. + if (i != obj->rx_tail) { + obj->rx_buff[obj->rx_head] = c; + obj->rx_head = i; + } + + #if ENABLED(EMERGENCY_PARSER) + emergency_parser.update(static_cast(this)->emergency_state, c); + #endif } - - #if ENABLED(EMERGENCY_PARSER) - emergency_parser.update(static_cast(this)->emergency_state, c); - #endif } -} + +#endif // !SERIAL_DMA #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h index bf861fb8a7..73ab77d8d4 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.h +++ b/Marlin/src/HAL/STM32/MarlinSerial.h @@ -27,23 +27,54 @@ #include "../../feature/e_parser.h" #endif +#if ENABLED(SERIAL_DMA) + #include "HardwareSerial.h" +#endif + #include "../../core/serial_hook.h" -typedef void (*usart_rx_callback_t)(serial_t * obj); +#ifdef USBCON + #include + typedef ForwardSerial1Class< decltype(SerialUSB) > DefaultSerial1; + extern DefaultSerial1 MSerialUSB; + #define USB_SERIAL_PORT(...) MSerialUSB +#endif -struct MarlinSerial : public HardwareSerial { - MarlinSerial(void *peripheral, usart_rx_callback_t rx_callback) : - HardwareSerial(peripheral), _rx_callback(rx_callback) - { } +#define SERIAL_INDEX_MIN 1 +#define SERIAL_INDEX_MAX 9 +#include "../shared/serial_ports.h" - void begin(unsigned long baud, uint8_t config); - inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } +#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() +#endif - void _rx_complete_irq(serial_t *obj); +#if ENABLED(SERIAL_DMA) -protected: - usart_rx_callback_t _rx_callback; -}; + struct MarlinSerial : public HAL_HardwareSerial { + MarlinSerial(void *peripheral) : HAL_HardwareSerial(peripheral) { } + void begin(unsigned long baud, uint8_t config); + inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } + }; + +#else // Arduino non-DMA + + typedef void (*usart_rx_callback_t)(serial_t * obj); + + struct MarlinSerial : public HardwareSerial { + MarlinSerial(void *peripheral, usart_rx_callback_t rx_callback) + : HardwareSerial(peripheral), _rx_callback(rx_callback) { } + + void begin(unsigned long baud, uint8_t config); + inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } + + void _rx_complete_irq(serial_t *obj); + FORCE_INLINE static uint8_t buffer_overruns() { return 0; } // Not implemented. Void to avoid platform-dependent code. + + protected: + usart_rx_callback_t _rx_callback; + }; + +#endif typedef Serial1Class MSerialT; extern MSerialT MSerial1; diff --git a/Marlin/src/HAL/STM32/MinSerial.cpp b/Marlin/src/HAL/STM32/MinSerial.cpp index b0fcff20c1..a27bc35a14 100644 --- a/Marlin/src/HAL/STM32/MinSerial.cpp +++ b/Marlin/src/HAL/STM32/MinSerial.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -45,7 +44,7 @@ struct USARTMin { volatile uint32_t CR2; }; -#if WITHIN(SERIAL_PORT, 1, 6) +#if WITHIN(SERIAL_PORT, 1, 9) // Depending on the CPU, the serial port is different for USART1 static const uintptr_t regsAddr[] = { TERN(STM32F1xx, 0x40013800, 0x40011000), // USART1 @@ -53,7 +52,10 @@ struct USARTMin { 0x40004800, // USART3 0x40004C00, // UART4_BASE 0x40005000, // UART5_BASE - 0x40011400 // USART6 + 0x40011400, // USART6 + 0x40007800, // UART7_BASE + 0x40007C00, // UART8_BASE + 0x40011800 // UART9_BASE }; static USARTMin * regs = (USARTMin*)regsAddr[SERIAL_PORT - 1]; #endif @@ -116,7 +118,7 @@ static void TXBegin() { // A SW memory barrier, to ensure GCC does not overoptimize loops #define sw_barrier() __asm__ volatile("": : :"memory"); static void TX(char c) { - #if WITHIN(SERIAL_PORT, 1, 6) + #if WITHIN(SERIAL_PORT, 1, 9) constexpr uint32_t usart_sr_txe = _BV(7); while (!(regs->SR & usart_sr_txe)) { hal.watchdog_refresh(); @@ -135,18 +137,18 @@ void install_min_serial() { } #if NONE(DYNAMIC_VECTORTABLE, STM32F0xx, STM32G0xx) // Cortex M0 can't jump to a symbol that's too far from the current function, so we work around this in exception_arm.cpp -extern "C" { - __attribute__((naked)) void JumpHandler_ASM() { - __asm__ __volatile__ ( - "b CommonHandler_ASM\n" - ); + extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler(); } - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler(); -} #endif #endif // POSTMORTEM_DEBUGGING diff --git a/Marlin/src/HAL/STM32/README.md b/Marlin/src/HAL/STM32/README.md index 7680df6654..cf8aa50d50 100644 --- a/Marlin/src/HAL/STM32/README.md +++ b/Marlin/src/HAL/STM32/README.md @@ -3,9 +3,10 @@ This HAL is intended to act as the generic STM32 HAL for all STM32 chips (The whole F, H and L family). Currently it supports: - * STM32F0xx - * STM32F1xx - * STM32F4xx - * STM32F7xx + +- STM32F0xx +- STM32F1xx +- STM32F4xx +- STM32F7xx Targeting the official [Arduino STM32 Core](https://github.com/stm32duino/Arduino_Core_STM32). diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index a00186e0e7..eb535b1eb1 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -40,8 +39,8 @@ static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO); // This must be called after the STM32 Servo class has initialized the timer. -// It may only be needed after the first call to attach(), but it is possible -// that is is necessary after every detach() call. To be safe this is currently +// It may only be needed after the first call to attach(), but it's possible +// that this is needed after every detach() call. To be safe this is currently // called after every call to attach(). static void fixServoTimerInterruptPriority() { NVIC_SetPriority(getTimerUpIrq(TIMER_SERVO), servo_interrupt_priority); diff --git a/Marlin/src/HAL/STM32/Servo.h b/Marlin/src/HAL/STM32/Servo.h index 1527e753b6..95ecb5d977 100644 --- a/Marlin/src/HAL/STM32/Servo.h +++ b/Marlin/src/HAL/STM32/Servo.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32/dogm/u8g_com_stm32duino_swspi.cpp new file mode 100644 index 0000000000..68c6430538 --- /dev/null +++ b/Marlin/src/HAL/STM32/dogm/u8g_com_stm32duino_swspi.cpp @@ -0,0 +1,136 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm / Ryan Power + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 HAL_STM32 + +#include "../../../inc/MarlinConfig.h" + +#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) + +#include +#include "../../shared/HAL_SPI.h" + +#define nop asm volatile ("\tnop\n") + +static inline uint8_t swSpiTransfer_mode_0(uint8_t b) { + for (uint8_t i = 0; i < 8; ++i) { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + WRITE(DOGLCD_SCK, HIGH); + WRITE(DOGLCD_MOSI, state); + b <<= 1; + WRITE(DOGLCD_SCK, LOW); + } + return b; +} + +static inline uint8_t swSpiTransfer_mode_3(uint8_t b) { + for (uint8_t i = 0; i < 8; ++i) { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + WRITE(DOGLCD_SCK, LOW); + WRITE(DOGLCD_MOSI, state); + b <<= 1; + WRITE(DOGLCD_SCK, HIGH); + } + return b; +} + +static void u8g_sw_spi_shift_out(uint8_t val) { + #if U8G_SPI_USE_MODE_3 + swSpiTransfer_mode_3(val); + #else + swSpiTransfer_mode_0(val); + #endif +} + +static void swSpiInit() { + #if PIN_EXISTS(LCD_RESET) + SET_OUTPUT(LCD_RESET_PIN); + #endif + SET_OUTPUT(DOGLCD_A0); + OUT_WRITE(DOGLCD_SCK, LOW); + OUT_WRITE(DOGLCD_MOSI, LOW); + OUT_WRITE(DOGLCD_CS, HIGH); +} + +uint8_t u8g_com_HAL_STM32_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + switch (msg) { + case U8G_COM_MSG_INIT: + swSpiInit(); + break; + + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_RESET: + #if PIN_EXISTS(LCD_RESET) + WRITE(LCD_RESET_PIN, arg_val); + #endif + break; + + case U8G_COM_MSG_CHIP_SELECT: + #if U8G_SPI_USE_MODE_3 // This LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + WRITE(DOGLCD_SCK, HIGH); // Set SCK to mode 3 idle state before CS goes active + WRITE(DOGLCD_CS, LOW); + nop; // hold SCK high for a few ns + nop; + } + else { + WRITE(DOGLCD_CS, HIGH); + WRITE(DOGLCD_SCK, LOW); // Set SCK to mode 0 idle state after CS goes inactive + } + #else + WRITE(DOGLCD_CS, !arg_val); + #endif + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_sw_spi_shift_out(arg_val); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t *ptr = (uint8_t *)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(*ptr++); + arg_val--; + } + } break; + + case U8G_COM_MSG_WRITE_SEQ_P: { + uint8_t *ptr = (uint8_t *)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } break; + + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + WRITE(DOGLCD_A0, arg_val); + break; + } + return 1; +} + +#endif // HAS_MARLINUI_U8GLIB && FORCE_SOFT_SPI +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32/eeprom/eeprom_bl24cxx.cpp similarity index 88% rename from Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp rename to Marlin/src/HAL/STM32/eeprom/eeprom_bl24cxx.cpp index f30b3dedb2..8240f15d3a 100644 --- a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp +++ b/Marlin/src/HAL/STM32/eeprom/eeprom_bl24cxx.cpp @@ -20,7 +20,7 @@ * */ -#include "../platforms.h" +#include "../../platforms.h" #ifdef HAL_STM32 @@ -29,12 +29,12 @@ * with simple implementations supplied by Marlin. */ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(IIC_BL24CXX_EEPROM) -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" // // PersistentStore @@ -44,7 +44,7 @@ #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM." #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } @@ -53,7 +53,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui uint16_t written = 0; while (size--) { uint8_t v = *value; - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes @@ -71,8 +71,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t * const p = (uint8_t * const)pos; - uint8_t c = eeprom_read_byte(p); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom/eeprom_flash.cpp similarity index 72% rename from Marlin/src/HAL/STM32/eeprom_flash.cpp rename to Marlin/src/HAL/STM32/eeprom/eeprom_flash.cpp index 7c8cc8dd21..5a9062e956 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../platforms.h" +#include "../../platforms.h" #ifdef HAL_STM32 -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(FLASH_EEPROM_EMULATION) -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_api.h" // Better: "utility/stm32_eeprom.h", but only after updating stm32duino to 2.0.0 // Use EEPROM.h for compatibility, for now. @@ -51,10 +50,10 @@ #if ENABLED(FLASH_EEPROM_LEVELING) - #include "stm32_def.h" + #include #define DEBUG_OUT ENABLED(EEPROM_CHITCHAT) - #include "../../core/debug_out.h" + #include "../../../core/debug_out.h" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB @@ -64,7 +63,7 @@ #define FLASH_SECTOR (FLASH_SECTOR_TOTAL - 1) #endif #ifndef FLASH_UNIT_SIZE - #define FLASH_UNIT_SIZE 0x20000 // 128kB + #define FLASH_UNIT_SIZE 0x20000 // 128K #endif #ifndef FLASH_ADDRESS_START @@ -75,13 +74,13 @@ #define EEPROM_SLOTS ((FLASH_UNIT_SIZE) / (MARLIN_EEPROM_SIZE)) #define SLOT_ADDRESS(slot) (FLASH_ADDRESS_START + (slot * (MARLIN_EEPROM_SIZE))) - #define UNLOCK_FLASH() if (!flash_unlocked) { \ - HAL_FLASH_Unlock(); \ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | \ - FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); \ - flash_unlocked = true; \ - } - #define LOCK_FLASH() if (flash_unlocked) { HAL_FLASH_Lock(); flash_unlocked = false; } + #ifdef STM32H7xx + #define FLASHWORD_SIZE 32U // STM32H7xx a FLASHWORD is 32 bytes (256 bits) + #define FLASH_FLAGS_TO_CLEAR (FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGSERR) + #else + #define FLASHWORD_SIZE 4U // STM32F4xx a FLASHWORD is 4 bytes sizeof(uint32_t) + #define FLASH_FLAGS_TO_CLEAR (FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR) + #endif #define EMPTY_UINT32 ((uint32_t)-1) #define EMPTY_UINT8 ((uint8_t)-1) @@ -89,20 +88,20 @@ static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static int current_slot = -1; - static_assert(0 == MARLIN_EEPROM_SIZE % 4, "MARLIN_EEPROM_SIZE must be a multiple of 4"); // Ensure copying as uint32_t is safe + static_assert(0 == MARLIN_EEPROM_SIZE % FLASHWORD_SIZE, "MARLIN_EEPROM_SIZE must be a multiple of the FLASHWORD size"); // Ensure copying as uint32_t is safe static_assert(0 == FLASH_UNIT_SIZE % MARLIN_EEPROM_SIZE, "MARLIN_EEPROM_SIZE must divide evenly into your FLASH_UNIT_SIZE"); static_assert(FLASH_UNIT_SIZE >= MARLIN_EEPROM_SIZE, "FLASH_UNIT_SIZE must be greater than or equal to your MARLIN_EEPROM_SIZE"); static_assert(IS_FLASH_SECTOR(FLASH_SECTOR), "FLASH_SECTOR is invalid"); static_assert(IS_POWER_OF_2(FLASH_UNIT_SIZE), "FLASH_UNIT_SIZE should be a power of 2, please check your chip's spec sheet"); -#endif +#endif // FLASH_EEPROM_LEVELING static bool eeprom_data_written = false; #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(E2END + 1) #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { @@ -126,13 +125,13 @@ bool PersistentStore::access_start() { } if (current_slot == -1) { // We didn't find anything, so we'll just initialize to empty - for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8; + for (int i = 0; i < long(MARLIN_EEPROM_SIZE); i++) ram_eeprom[i] = EMPTY_UINT8; current_slot = EEPROM_SLOTS; } else { // load current settings uint8_t *eeprom_data = (uint8_t *)SLOT_ADDRESS(current_slot); - for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i]; + for (int i = 0; i < long(MARLIN_EEPROM_SIZE); i++) ram_eeprom[i] = eeprom_data[i]; DEBUG_ECHOLNPGM("EEPROM loaded from slot ", current_slot, "."); } eeprom_data_written = false; @@ -148,11 +147,15 @@ bool PersistentStore::access_start() { bool PersistentStore::access_finish() { if (eeprom_data_written) { + #ifdef STM32F4xx // MCU may come up with flash error bits which prevent some flash operations. // Clear flags prior to flash operations to prevent errors. __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); #endif + #ifdef STM32H7xx + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGSERR); + #endif #if ENABLED(FLASH_EEPROM_LEVELING) @@ -171,7 +174,12 @@ bool PersistentStore::access_finish() { EraseInitStruct.NbSectors = 1; current_slot = EEPROM_SLOTS - 1; - UNLOCK_FLASH(); + + if (!flash_unlocked) { + HAL_FLASH_Unlock(); + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAGS_TO_CLEAR); + flash_unlocked = true; + } TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); hal.isr_off(); @@ -182,26 +190,37 @@ bool PersistentStore::access_finish() { DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status); DEBUG_ECHOLNPGM("GetError=", HAL_FLASH_GetError()); DEBUG_ECHOLNPGM("SectorError=", SectorError); - LOCK_FLASH(); + if (flash_unlocked) { + HAL_FLASH_Lock(); + flash_unlocked = false; + } return false; } } - UNLOCK_FLASH(); + if (!flash_unlocked) { + HAL_FLASH_Unlock(); + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAGS_TO_CLEAR); + flash_unlocked = true; + } - uint32_t offset = 0; - uint32_t address = SLOT_ADDRESS(current_slot); - uint32_t address_end = address + MARLIN_EEPROM_SIZE; - uint32_t data = 0; + uint32_t offset = 0, + address = SLOT_ADDRESS(current_slot), + address_end = address + MARLIN_EEPROM_SIZE; bool success = true; while (address < address_end) { - memcpy(&data, ram_eeprom + offset, sizeof(uint32_t)); - status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, data); + #ifdef STM32H7xx + status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_FLASHWORD, address, uint32_t(ram_eeprom + offset)); + #else + //memcpy(&data, ram_eeprom + offset, sizeof(data)); // IRON, IMPROVED + //status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, data); + status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, *(uint32_t*)(ram_eeprom + offset)); // IRON, OPTIMIZED + #endif if (status == HAL_OK) { - address += sizeof(uint32_t); - offset += sizeof(uint32_t); + address += FLASHWORD_SIZE; + offset += FLASHWORD_SIZE; } else { DEBUG_ECHOLNPGM("HAL_FLASH_Program=", status); @@ -212,7 +231,10 @@ bool PersistentStore::access_finish() { } } - LOCK_FLASH(); + if (flash_unlocked) { + HAL_FLASH_Lock(); + flash_unlocked = false; + } if (success) { eeprom_data_written = false; @@ -221,7 +243,8 @@ bool PersistentStore::access_finish() { return success; - #else + #else // !FLASH_EEPROM_LEVELING + // The following was written for the STM32F4 but may work with other MCUs as well. // Most STM32F4 flash does not allow reading from flash during erase operations. // This takes about a second on a STM32F407 with a 128kB sector used as EEPROM. @@ -235,7 +258,8 @@ bool PersistentStore::access_finish() { TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; - #endif + + #endif // !FLASH_EEPROM_LEVELING } return true; @@ -244,14 +268,15 @@ bool PersistentStore::access_finish() { bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t v = *value; + const int p = REAL_EEPROM_ADDR(pos); #if ENABLED(FLASH_EEPROM_LEVELING) - if (v != ram_eeprom[pos]) { - ram_eeprom[pos] = v; + if (v != ram_eeprom[p]) { + ram_eeprom[p] = v; eeprom_data_written = true; } #else - if (v != eeprom_buffered_read_byte(pos)) { - eeprom_buffered_write_byte(pos, v); + if (v != eeprom_buffered_read_byte(p)) { + eeprom_buffered_write_byte(p, v); eeprom_data_written = true; } #endif @@ -264,7 +289,8 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - const uint8_t c = TERN(FLASH_EEPROM_LEVELING, ram_eeprom[pos], eeprom_buffered_read_byte(pos)); + const int p = REAL_EEPROM_ADDR(pos); + const uint8_t c = TERN(FLASH_EEPROM_LEVELING, ram_eeprom[p], eeprom_buffered_read_byte(p)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32/eeprom/eeprom_if_iic.cpp similarity index 88% rename from Marlin/src/HAL/STM32/eeprom_if_iic.cpp rename to Marlin/src/HAL/STM32/eeprom/eeprom_if_iic.cpp index ad8712c0c0..2733c8f283 100644 --- a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/STM32/eeprom/eeprom_if_iic.cpp @@ -20,7 +20,7 @@ * */ -#include "../platforms.h" +#include "../../platforms.h" #ifdef HAL_STM32 @@ -29,12 +29,12 @@ * Enable USE_SHARED_EEPROM if not supplied by the framework. */ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(IIC_BL24CXX_EEPROM) -#include "../../libs/BL24CXX.h" -#include "../shared/eeprom_if.h" +#include "../../../libs/BL24CXX.h" +#include "../../shared/eeprom_if.h" void eeprom_init() { BL24CXX::init(); } @@ -44,7 +44,7 @@ void eeprom_init() { BL24CXX::init(); } void eeprom_write_byte(uint8_t *pos, uint8_t value) { const unsigned eeprom_address = (unsigned)pos; - return BL24CXX::writeOneByte(eeprom_address, value); + BL24CXX::writeOneByte(eeprom_address, value); } uint8_t eeprom_read_byte(uint8_t *pos) { diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom/eeprom_sdcard.cpp similarity index 86% rename from Marlin/src/HAL/STM32/eeprom_sdcard.cpp rename to Marlin/src/HAL/STM32/eeprom/eeprom_sdcard.cpp index 473b656f9a..64da3745d1 100644 --- a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom/eeprom_sdcard.cpp @@ -20,7 +20,7 @@ * */ -#include "../platforms.h" +#include "../../platforms.h" #ifdef HAL_STM32 @@ -28,19 +28,19 @@ * Implementation of EEPROM settings in SD Card */ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "../shared/eeprom_api.h" -#include "../../sd/cardreader.h" +#include "../../shared/eeprom_api.h" +#include "../../../sd/cardreader.h" #define EEPROM_FILENAME "eeprom.dat" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } #define _ALIGN(x) __attribute__ ((aligned(x))) static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE]; @@ -48,13 +48,13 @@ static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE]; bool PersistentStore::access_start() { if (!card.isMounted()) return false; - SdFile file, root = card.getroot(); + MediaFile file, root = card.getroot(); if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) return true; int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE); if (bytes_read < 0) return false; - for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++) + for (; bytes_read < long(MARLIN_EEPROM_SIZE); bytes_read++) HAL_eeprom_data[bytes_read] = 0xFF; file.close(); return true; @@ -63,7 +63,7 @@ bool PersistentStore::access_start() { bool PersistentStore::access_finish() { if (!card.isMounted()) return false; - SdFile file, root = card.getroot(); + MediaFile file, root = card.getroot(); int bytes_written = 0; if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE); diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom/eeprom_sram.cpp similarity index 85% rename from Marlin/src/HAL/STM32/eeprom_sram.cpp rename to Marlin/src/HAL/STM32/eeprom/eeprom_sram.cpp index 687e7f55c2..a9d62ec29c 100644 --- a/Marlin/src/HAL/STM32/eeprom_sram.cpp +++ b/Marlin/src/HAL/STM32/eeprom/eeprom_sram.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,21 +19,21 @@ * along with this program. If not, see . * */ -#include "../platforms.h" +#include "../../platforms.h" #ifdef HAL_STM32 -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(SRAM_EEPROM_EMULATION) -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/STM32/eeprom/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom/eeprom_wired.cpp new file mode 100644 index 0000000000..fa45e6c40d --- /dev/null +++ b/Marlin/src/HAL/STM32/eeprom/eeprom_wired.cpp @@ -0,0 +1,79 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../platforms.h" + +#ifdef HAL_STM32 + +#include "../../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } + +bool PersistentStore::access_start() { eeprom_init(); return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; + while (size--) { + uint8_t v = *value; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! + eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + // Read from either external EEPROM, program flash or Backup SRAM + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +#endif // USE_WIRED_EEPROM +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h index d2f20ba1c7..e17b8a4c8e 100644 --- a/Marlin/src/HAL/STM32/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32/endstop_interrupts.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -29,33 +28,34 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); - TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index b34555b8c8..f8501545a0 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -29,7 +28,7 @@ GPIO_TypeDef* FastIOPortMap[LastPort + 1] = { 0 }; void FastIO_init() { - LOOP_L_N(i, NUM_DIGITAL_PINS) + for (uint8_t i = 0; i < NUM_DIGITAL_PINS; ++i) FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i])); } diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h index 4a48954471..a92bbc492e 100644 --- a/Marlin/src/HAL/STM32/fastio.h +++ b/Marlin/src/HAL/STM32/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -78,6 +77,7 @@ void FastIO_init(); // Must be called before using fast io macros #define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) //!< Input with Pull-up activation #define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) //!< Input with Pull-down activation #define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) +#define SET_OUTPUT_OD(IO) OUT_WRITE_OD(IO, LOW) #define SET_PWM(IO) _SET_MODE(IO, PWM) #define IS_INPUT(IO) diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h index 451c94f25d..f345b925bb 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h @@ -21,7 +21,7 @@ */ #pragma once -#if BOTH(SDSUPPORT, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) +#if ALL(HAS_MEDIA, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) #define HAS_SD_HOST_DRIVE 1 #endif @@ -30,6 +30,3 @@ #undef F_CPU #define F_CPU BOARD_F_CPU #endif - -// The Sensitive Pins array is not optimizable -#define RUNTIME_ONLY_ANALOG_TO_DIGITAL diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h index 18826e11d2..8d72e720c1 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h @@ -24,6 +24,11 @@ // If no real or emulated EEPROM selected, fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif + +// Some STM32F4 boards may lose steps when saving to EEPROM during print (PR #17946) +#if ALL(STM32F4xx, FLASH_EEPROM_EMULATION) && PRINTCOUNTER_SAVE_INTERVAL > 0 + #define PRINTCOUNTER_SYNC +#endif diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_type.h b/Marlin/src/HAL/STM32/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/STM32/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 0f1a2acaa4..616f96eba0 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -28,8 +28,7 @@ // #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" //#endif - -#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT) +#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise #if USE_FALLBACK_EEPROM #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." @@ -37,13 +36,8 @@ #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." #endif -#if defined(STM32F4xx) && BOTH(PRINTCOUNTER, FLASH_EEPROM_EMULATION) - #warning "FLASH_EEPROM_EMULATION may cause long delays when writing and should not be used while printing." - #error "Disable PRINTCOUNTER or choose another EEPROM emulation." -#endif - -#if !defined(STM32F4xx) && ENABLED(FLASH_EEPROM_LEVELING) - #error "FLASH_EEPROM_LEVELING is currently only supported on STM32F4 hardware." +#if NONE(STM32F4xx, STM32H7xx) && ENABLED(FLASH_EEPROM_LEVELING) + #error "FLASH_EEPROM_LEVELING is currently only supported on STM32F4/H7 hardware." // IRON #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) @@ -55,3 +49,67 @@ #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) && NOT_TARGET(STM32H7xx, STM32F4xx, STM32F1xx) #error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are currently only supported on STM32H7, STM32F4 and STM32F1 hardware." #endif + +#if TEMP_SENSOR_SOC && defined(ATEMP) && TEMP_SOC_PIN != ATEMP + #error "TEMP_SENSOR_SOC requires 'TEMP_SOC_PIN ATEMP' on STM32." +#endif + +/** + * Check for common serial pin conflicts + */ +#define _CHECK_SERIAL_PIN(N) (( \ + BTN_EN1 == N || BTN_EN2 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN0_PIN == N || \ + SDIO_D2_PIN == N || SDIO_D3_PIN == N || SDIO_CK_PIN == N || SDIO_CMD_PIN == N || \ + Y_STEP_PIN == N || Y_ENABLE_PIN == N || E0_ENABLE_PIN == N || POWER_LOSS_PIN == N \ + )) +#define CHECK_SERIAL_PIN(T,N) defined(UART##N##_##T##_PIN) && _CHECK_SERIAL_PIN(UART##N##_##T##_PIN) +#if SERIAL_IN_USE(1) + #if CHECK_SERIAL_PIN(TX,1) + #error "Serial Port 1 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX,1) + #error "Serial Port 1 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(2) + #if CHECK_SERIAL_PIN(TX,2) + #error "Serial Port 2 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX,2) + #error "Serial Port 2 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(3) + #if CHECK_SERIAL_PIN(TX,3) + #error "Serial Port 3 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX,3) + #error "Serial Port 3 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(4) + #if CHECK_SERIAL_PIN(TX,4) + #error "Serial Port 4 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX,4) + #error "Serial Port 4 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(5) + #if CHECK_SERIAL_PIN(TX,5) + #error "Serial Port 5 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX,5) + #error "Serial Port 5 RX IO pins conflict with another pin on the board." + #endif +#endif +#if SERIAL_IN_USE(6) + #if CHECK_SERIAL_PIN(TX,6) + #error "Serial Port 6 TX IO pins conflict with another pin on the board." + #endif + #if CHECK_SERIAL_PIN(RX,6) + #error "Serial Port 6 RX IO pins conflict with another pin on the board." + #endif +#endif +#undef CHECK_SERIAL_PIN +#undef _CHECK_SERIAL_PIN diff --git a/Marlin/src/HAL/STM32/msc_sd.h b/Marlin/src/HAL/STM32/msc_sd.h deleted file mode 100644 index a8e5349f7c..0000000000 --- a/Marlin/src/HAL/STM32/msc_sd.h +++ /dev/null @@ -1,18 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -void MSC_SD_init(); diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index 55c64c8681..89e2514af0 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -21,6 +21,26 @@ */ #pragma once +/** + * Pins Debugging for STM32 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + #include #ifndef NUM_DIGITAL_PINS @@ -34,11 +54,11 @@ * that a CPU has. * * VARIABLES: - * Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and - * digitalWrite commands and by M42. - * - does not contain port/pin info - * - is not in port/pin order - * - typically a variant will only assign Ard_num to port/pins that are actually used + * A - Arduino pin number - defined by the platform. It is used by digitalRead and + * digitalWrite commands and by M42. + * - does not contain port/pin info + * - is not in port/pin order + * - typically a variant will only assign Ard_num to port/pins that are actually used * Index - M43 counter - only used to get Ard_num * x - a parameter/argument used to search the pin_array to try to find a signal name * associated with a Ard_num @@ -98,57 +118,53 @@ const XrefInfo pin_xref[] PROGMEM = { #define MODE_PIN_ALT 2 // Alternate function mode #define MODE_PIN_ANALOG 3 // Analog mode -#define PIN_NUM(P) (P & 0x000F) -#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1') -#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 ) -#define PORT_NUM(P) ((P >> 4) & 0x0007) -#define PORT_ALPHA(P) ('A' + (P >> 4)) +#define PIN_NUM(P) ((P) & 0x000F) +#define PIN_NUM_ALPHA_LEFT(P) ((((P) & 0x000F) < 10) ? ('0' + ((P) & 0x000F)) : '1') +#define PIN_NUM_ALPHA_RIGHT(P) ((((P) & 0x000F) > 9) ? ('0' + ((P) & 0x000F) - 10) : 0 ) +#define PORT_NUM(P) (((P) >> 4) & 0x0007) +#define PORT_ALPHA(P) ('A' + ((P) >> 4)) -/** - * Translation of routines & variables used by pinsDebug.h - */ - -#if PA0 >= NUM_DIGITAL_PINS +#if NUM_ANALOG_FIRST >= NUM_DIGITAL_PINS #define HAS_HIGH_ANALOG_PINS 1 #endif -#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS) -#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL) -#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads -#define PRINT_PIN(Q) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PORT(ANUM) port_print(ANUM) -#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine - -// x is a variable used to search pin_array -#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) -#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin) -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#ifndef NUM_ANALOG_LAST + #define NUM_ANALOG_LAST ((NUM_ANALOG_FIRST) + (NUM_ANALOG_INPUTS) - 1) +#endif +#define NUMBER_PINS_TOTAL ((NUM_DIGITAL_PINS) + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS)) +#define isValidPin(P) (WITHIN(P, 0, (NUM_DIGITAL_PINS) - 1) || TERN0(HAS_HIGH_ANALOG_PINS, WITHIN(P, NUM_ANALOG_FIRST, NUM_ANALOG_LAST))) +#define digitalRead_mod(A) extDigitalRead(A) // must use Arduino pin numbers when doing reads +#define printPinNumber(Q) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define digitalPinToAnalogIndex(P) -1 // will report analog pin number in the print port routine +#define getPinIsDigitalByIndex(x) bool(pin_array[x].is_digital) +#define getPinByIndex(x) pin_t(pin_array[x].pin) +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin // // Pin Mapping for M43 // -#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num +#define GET_PIN_MAP_PIN_M43(x) pin_xref[x].Ard_num #ifndef M43_NEVER_TOUCH - #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) - #ifdef KILL_PIN - #define M43_NEVER_TOUCH(Index) m43_never_touch(Index) + #define _M43_NEVER_TOUCH(x) WITHIN(x, 9, 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) + #if PIN_EXISTS(KILL) + #define M43_NEVER_TOUCH(x) m43_never_touch(x) - bool m43_never_touch(const pin_t Index) { + bool m43_never_touch(const pin_t index) { static pin_t M43_kill_index = -1; if (M43_kill_index < 0) for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++) if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break; - return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB + return _M43_NEVER_TOUCH(index) || index == M43_kill_index; // KILL_PIN and SERIAL/USB } #else - #define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index) + #define M43_NEVER_TOUCH(index) _M43_NEVER_TOUCH(index) #endif #endif -uint8_t get_pin_mode(const pin_t Ard_num) { - const PinName dp = digitalPinToPinName(Ard_num); +uint8_t get_pin_mode(const pin_t pin) { + const PinName dp = digitalPinToPinName(pin); uint32_t ll_pin = STM_LL_GPIO_PIN(dp); GPIO_TypeDef *port = get_GPIO_Port(STM_PORT(dp)); uint32_t mode = LL_GPIO_GetPinMode(port, ll_pin); @@ -162,41 +178,41 @@ uint8_t get_pin_mode(const pin_t Ard_num) { } } -bool GET_PINMODE(const pin_t Ard_num) { - const uint8_t pin_mode = get_pin_mode(Ard_num); +bool getValidPinMode(const pin_t pin) { + const uint8_t pin_mode = get_pin_mode(pin); return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM } -int8_t digital_pin_to_analog_pin(const pin_t Ard_num) { - if (WITHIN(Ard_num, NUM_ANALOG_FIRST, NUM_ANALOG_FIRST + NUM_ANALOG_INPUTS - 1)) - return Ard_num - NUM_ANALOG_FIRST; +int8_t digital_pin_to_analog_pin(const pin_t pin) { + if (WITHIN(pin, NUM_ANALOG_FIRST, NUM_ANALOG_LAST)) + return pin - NUM_ANALOG_FIRST; - const uint32_t ind = digitalPinToAnalogInput(Ard_num); + const int8_t ind = digitalPinToAnalogIndex(pin); return (ind < NUM_ANALOG_INPUTS) ? ind : -1; } -bool IS_ANALOG(const pin_t Ard_num) { - return get_pin_mode(Ard_num) == MODE_PIN_ANALOG; +bool isAnalogPin(const pin_t pin) { + return get_pin_mode(pin) == MODE_PIN_ANALOG; } -bool is_digital(const pin_t Ard_num) { - const uint8_t pin_mode = get_pin_mode(pin_array[Ard_num].pin); +bool is_digital(const pin_t pin) { + const uint8_t pin_mode = get_pin_mode(pin_array[pin].pin); return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; } -void port_print(const pin_t Ard_num) { +void printPinPort(const pin_t pin) { char buffer[16]; - pin_t Index; - for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++) - if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break; + pin_t index; + for (index = 0; index < NUMBER_PINS_TOTAL; index++) + if (pin == GET_PIN_MAP_PIN_M43(index)) break; - const char * ppa = pin_xref[Index].Port_pin_alpha; + const char * ppa = pin_xref[index].Port_pin_alpha; sprintf_P(buffer, PSTR("%s"), ppa); SERIAL_ECHO(buffer); if (ppa[3] == '\0') SERIAL_CHAR(' '); // print analog pin number - const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num); + const int8_t Port_pin = digital_pin_to_analog_pin(pin); if (Port_pin >= 0) { sprintf_P(buffer, PSTR(" (A%d) "), Port_pin); SERIAL_ECHO(buffer); @@ -206,10 +222,12 @@ void port_print(const pin_t Ard_num) { SERIAL_ECHO_SP(7); // Print number to be used with M42 - int calc_p = Ard_num % (NUM_DIGITAL_PINS + 1); - if (Ard_num > NUM_DIGITAL_PINS && calc_p > 7) calc_p += 8; - SERIAL_ECHOPGM(" M42 P", calc_p); - SERIAL_CHAR(' '); + int calc_p = pin; + if (pin > NUM_DIGITAL_PINS) { + calc_p -= NUM_ANALOG_FIRST; + if (calc_p > 7) calc_p += 8; + } + SERIAL_ECHO(F(" M42 P"), calc_p, C(' ')); if (calc_p < 100) { SERIAL_CHAR(' '); if (calc_p < 10) @@ -217,15 +235,15 @@ void port_print(const pin_t Ard_num) { } } -bool pwm_status(const pin_t Ard_num) { - return get_pin_mode(Ard_num) == MODE_PIN_ALT; +bool pwm_status(const pin_t pin) { + return get_pin_mode(pin) == MODE_PIN_ALT; } -void pwm_details(const pin_t Ard_num) { +void printPinPWM(const pin_t pin) { #ifndef STM32F1xx - if (pwm_status(Ard_num)) { + if (pwm_status(pin)) { uint32_t alt_all = 0; - const PinName dp = digitalPinToPinName(Ard_num); + const PinName dp = digitalPinToPinName(pin); pin_t pin_number = uint8_t(PIN_NUM(dp)); const bool over_7 = pin_number >= 8; const uint8_t ind = over_7 ? 1 : 0; @@ -280,4 +298,4 @@ void pwm_details(const pin_t Ard_num) { #else // TODO: F1 doesn't support changing pins function, so we need to check the function of the PIN and if it's enabled #endif -} // pwm_details +} // printPinPWM diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/sd/msc_sd.cpp similarity index 50% rename from Marlin/src/HAL/STM32/msc_sd.cpp rename to Marlin/src/HAL/STM32/sd/msc_sd.cpp index a40bec9d64..9bb65aab4a 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/sd/msc_sd.cpp @@ -1,42 +1,55 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ -#include "../platforms.h" +#include "../../platforms.h" #ifdef HAL_STM32 -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_SD_HOST_DRIVE -#include "../shared/Marduino.h" +#include "../../../sd/cardreader.h" + #include "msc_sd.h" -#include "usbd_core.h" - -#include "../../sd/cardreader.h" +#include #include #include #define BLOCK_SIZE 512 #define PRODUCT_ID 0x29 +#ifndef SD_MULTIBLOCK_RETRY_CNT + #define SD_MULTIBLOCK_RETRY_CNT 1 +#elif SD_MULTIBLOCK_RETRY_CNT < 1 + #error "SD_MULTIBLOCK_RETRY_CNT must be greater than or equal to 1." +#endif + class Sd2CardUSBMscHandler : public USBMscHandler { public: DiskIODriver* diskIODriver() { - #if ENABLED(MULTI_VOLUME) + // TODO: Explore a variable shared volume, or auto share the un-mounted volume(s) + #if HAS_MULTI_VOLUME #if SHARED_VOLUME_IS(SD_ONBOARD) return &card.media_driver_sdcard; #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE) @@ -58,19 +71,29 @@ public: // single block if (blkLen == 1) { hal.watchdog_refresh(); - sd2card->writeBlock(blkAddr, pBuf); - return true; + return sd2card->writeBlock(blkAddr, pBuf); } // multi block optimization - sd2card->writeStart(blkAddr, blkLen); - while (blkLen--) { - hal.watchdog_refresh(); - sd2card->writeData(pBuf); - pBuf += BLOCK_SIZE; + bool done = false; + for (uint16_t rcount = SD_MULTIBLOCK_RETRY_CNT; !done && rcount--;) { + uint8_t *cBuf = pBuf; + sd2card->writeStart(blkAddr, blkLen); + bool okay = true; // Assume success + for (uint32_t i = blkLen; i--;) { + hal.watchdog_refresh(); + if (!sd2card->writeData(cBuf)) { // Write. Did it fail? + sd2card->writeStop(); // writeStop for new writeStart + okay = false; // Failed, so retry + break; // Go to while... below + } + cBuf += BLOCK_SIZE; + } + done = okay; // Done if no error occurred } - sd2card->writeStop(); - return true; + + if (done) sd2card->writeStop(); + return done; } bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) { @@ -78,24 +101,32 @@ public: // single block if (blkLen == 1) { hal.watchdog_refresh(); - sd2card->readBlock(blkAddr, pBuf); - return true; + return sd2card->readBlock(blkAddr, pBuf); } // multi block optimization - sd2card->readStart(blkAddr); - while (blkLen--) { - hal.watchdog_refresh(); - sd2card->readData(pBuf); - pBuf += BLOCK_SIZE; + bool done = false; + for (uint16_t rcount = SD_MULTIBLOCK_RETRY_CNT; !done && rcount--;) { + uint8_t *cBuf = pBuf; + sd2card->readStart(blkAddr); + bool okay = true; // Assume success + for (uint32_t i = blkLen; i--;) { + hal.watchdog_refresh(); + if (!sd2card->readData(cBuf)) { // Read. Did it fail? + sd2card->readStop(); // readStop for new readStart + okay = false; // Failed, so retry + break; // Go to while... below + } + cBuf += BLOCK_SIZE; + } + done = okay; // Done if no error occurred } - sd2card->readStop(); - return true; + + if (done) sd2card->readStop(); + return done; } - bool IsReady() { - return diskIODriver()->isReady(); - } + bool IsReady() { return diskIODriver()->isReady(); } }; Sd2CardUSBMscHandler usbMscHandler; diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.h b/Marlin/src/HAL/STM32/sd/msc_sd.h similarity index 71% rename from Marlin/src/lcd/e3v2/proui/meshviewer.h rename to Marlin/src/HAL/STM32/sd/msc_sd.h index 3aafe16984..20e738223c 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.h +++ b/Marlin/src/HAL/STM32/sd/msc_sd.h @@ -1,6 +1,7 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,20 +22,4 @@ */ #pragma once -/** - * Mesh Viewer for PRO UI - * Author: Miguel A. Risco-Castillo (MRISCOC) - * version: 3.14.1 - * Date: 2022/04/11 - */ - -class MeshViewerClass { -public: - float max, min; - void Draw(bool withsave = false); - void DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8_t sizey); -}; - -extern MeshViewerClass MeshViewer; - -void Goto_MeshViewer(); +void MSC_SD_init(); diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/sd/usb_host.cpp similarity index 93% rename from Marlin/src/HAL/STM32/usb_host.cpp rename to Marlin/src/HAL/STM32/sd/usb_host.cpp index d77f0b28e9..f411771c8a 100644 --- a/Marlin/src/HAL/STM32/usb_host.cpp +++ b/Marlin/src/HAL/STM32/sd/usb_host.cpp @@ -20,18 +20,17 @@ * */ -#include "../platforms.h" +#include "../../platforms.h" #ifdef HAL_STM32 -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" -#if BOTH(USE_OTG_USB_HOST, USBHOST) +#if ALL(USE_OTG_USB_HOST, USBHOST) #include "usb_host.h" -#include "../shared/Marduino.h" -#include "usbh_core.h" -#include "usbh_msc.h" +#include +#include USBH_HandleTypeDef hUsbHost; USBHost usb; @@ -44,7 +43,7 @@ static void USBH_UserProcess(USBH_HandleTypeDef *phost, uint8_t id) { break; case HOST_USER_DISCONNECTION: //SERIAL_ECHOLNPGM("APPLICATION_DISCONNECT"); - //usb.setUsbTaskState(USB_STATE_RUNNING); + usb.setUsbTaskState(USB_STATE_INIT); break; case HOST_USER_CLASS_ACTIVE: //SERIAL_ECHOLNPGM("APPLICATION_READY"); diff --git a/Marlin/src/HAL/STM32/usb_host.h b/Marlin/src/HAL/STM32/sd/usb_host.h similarity index 100% rename from Marlin/src/HAL/STM32/usb_host.h rename to Marlin/src/HAL/STM32/sd/usb_host.h diff --git a/Marlin/src/HAL/STM32/sdio.cpp b/Marlin/src/HAL/STM32/sdio.cpp index 41fe90b825..89df16628f 100644 --- a/Marlin/src/HAL/STM32/sdio.cpp +++ b/Marlin/src/HAL/STM32/sdio.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDIO_SUPPORT) +#if ENABLED(ONBOARD_SDIO) #include "sdio.h" @@ -238,7 +238,7 @@ void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { 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; + hdma_sdio.Init.Priority = DMA_PRIORITY_MEDIUM; __HAL_LINKDMA(&hsd, hdmarx, hdma_sdio); __HAL_LINKDMA(&hsd, hdmatx, hdma_sdio); @@ -286,6 +286,9 @@ void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { go_to_transfer_speed(); + hsd.Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_ENABLE; + hsd.Init.ClockDiv = 8; + #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined retry_Cnt = retryCnt; for (;;) { @@ -433,7 +436,10 @@ bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { #else uint8_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) return true; + while (retries--) { + if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) return true; + delay(10); + } return false; #endif @@ -447,5 +453,5 @@ uint32_t SDIO_GetCardSize() { return (uint32_t)(hsd.SdCard.BlockNbr) * (hsd.SdCard.BlockSize); } -#endif // SDIO_SUPPORT +#endif // ONBOARD_SDIO #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/spi_pins.h b/Marlin/src/HAL/STM32/spi_pins.h index 7f341a8c25..da6fa0d160 100644 --- a/Marlin/src/HAL/STM32/spi_pins.h +++ b/Marlin/src/HAL/STM32/spi_pins.h @@ -33,6 +33,3 @@ #ifndef SD_MOSI_PIN #define SD_MOSI_PIN PIN_SPI_MOSI #endif -#ifndef SD_SS_PIN - #define SD_SS_PIN PIN_SPI_SS -#endif diff --git a/Marlin/src/HAL/STM32/temp_soc.h b/Marlin/src/HAL/STM32/temp_soc.h new file mode 100644 index 0000000000..cc165dd5e4 --- /dev/null +++ b/Marlin/src/HAL/STM32/temp_soc.h @@ -0,0 +1,346 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef STM32F0xx + /* + STM32F030x4 STM32F030x6 STM32F030x8 STM32F030xC https://www.st.com/resource/en/datasheet/stm32f030f4.pdf + --> TS_CAL2 not defined in datasheet + STM32F031x4 STM32F031x6 https://www.st.com/resource/en/datasheet/stm32f031c4.pdf + STM32F038x6 https://www.st.com/resource/en/datasheet/stm32f038c6.pdf + STM32F042x4 STM32F042x6 https://www.st.com/resource/en/datasheet/stm32f042c4.pdf + STM32F048C6 STM32F048G6 STM32F048T6 https://www.st.com/resource/en/datasheet/stm32f048c6.pdf + STM32F051x4 STM32F051x6 STM32F051x8 https://www.st.com/resource/en/datasheet/dm00039193.pdf + STM32F058C8 STM32F058R8 STM32F058T8 https://www.st.com/resource/en/datasheet/stm32f058c8.pdf + STM32F070CB STM32F070RB STM32F070C6 STM32F070F6 https://www.st.com/resource/en/datasheet/stm32f070c6.pdf + --> TS_CAL2 not defined in datasheet + STM32F071x8 STM32F071xB https://www.st.com/resource/en/datasheet/stm32f071cb.pdf + STM32F072x8 STM32F072xB https://www.st.com/resource/en/datasheet/stm32f072c8.pdf + STM32F078CB STM32F078RB STM32F078VB https://www.st.com/resource/en/datasheet/stm32f078cb.pdf + STM32F091xB STM32F091xC https://www.st.com/resource/en/datasheet/stm32f091cc.pdf + STM32F098CC STM32F098RC STM32F098VC https://www.st.com/resource/en/datasheet/stm32f098cc.pdf + */ + #define TS_CAL1_TEMP 30 // Calibration temperature of TS_CAL1 (see specific SoC datasheet) + #define TS_CAL1_REGOFFSET 0x1FFFF7B8 // Memory address of TS_CAL1 for STM32F030x4/x6/x8/xC (see specific SoC datasheet) + #define TS_CAL2_TEMP 110 // Calibration temperature of TS_CAL2 (see specific SoC datasheet) + #define TS_CAL2_REGOFFSET 0x1FFFF7C2 // Memory address of TS_CAL2 for STM32F030x4/x6/x8/xC (see specific SoC datasheet) + +#elif defined(STM32F1xx) + /* + STM32F100xC STM32F100xD STM32F100xE https://www.st.com/resource/en/datasheet/stm32f100rc.pdf + --> V=1.41 + STM32F100x4 STM32F100x6 STM32F100x8 STM32F100xB https://www.st.com/resource/en/datasheet/stm32f100cb.pdf + --> V=1.41 + STM32F101x8 STM32F101xB https://www.st.com/resource/en/datasheet/stm32f101r8.pdf + STM32F101xC STM32F101xD STM32F101xE https://www.st.com/resource/en/datasheet/stm32f101rc.pdf + STM32F101x4 STM32F101x6 https://www.st.com/resource/en/datasheet/stm32f101c4.pdf + STM32F101xF STM32F101xG https://www.st.com/resource/en/datasheet/stm32f101vf.pdf + STM32F102x8 STM32F102xB https://www.st.com/resource/en/datasheet/stm32f102c8.pdf + --> V=1.42 / Slope=4.35 + STM32F102x4 STM32F102x6 https://www.st.com/resource/en/datasheet/stm32f102c4.pdf + --> V=1.42 / Slope=4.35 + STM32F103x8 STM32F103xB https://www.st.com/resource/en/datasheet/stm32f103c8.pdf + STM32F103xC STM32F103xD STM32F103xE https://www.st.com/resource/en/datasheet/stm32f103rc.pdf + STM32F103x4 STM32F103x6 https://www.st.com/resource/en/datasheet/stm32f103c4.pdf + STM32F103xF STM32F103xG https://www.st.com/resource/en/datasheet/stm32f103rg.pdf + STM32F105xx STM32F107xx https://www.st.com/resource/en/datasheet/stm32f105r8.pdf + */ + #define TS_TYPICAL_V 1.43 + #define TS_TYPICAL_TEMP 25 + #define TS_TYPICAL_SLOPE 4.3 + +#elif defined(STM32F2xx) + /* + STM32F205xx STM32F207xx https://www.st.com/resource/en/datasheet/stm32f205rb.pdf + STM32F215xx STM32F217xx https://www.st.com/resource/en/datasheet/stm32f215re.pdf + */ + #define TS_TYPICAL_V 0.76 + #define TS_TYPICAL_TEMP 25 + #define TS_TYPICAL_SLOPE 2.5 + +#elif defined(STM32F3xx) + /* + STM32F301x6 STM32F301x8 https://www.st.com/resource/en/datasheet/stm32f301c6.pdf + STM32F302xD STM32F302xE https://www.st.com/resource/en/datasheet/stm32f302re.pdf + STM32F302x6 STM32F302x8 https://www.st.com/resource/en/datasheet/stm32f302r6.pdf + STM32F302xB STM32F302xC https://www.st.com/resource/en/datasheet/stm32f302cb.pdf + STM32F303xD STM32F303xE https://www.st.com/resource/en/datasheet/stm32f303re.pdf + STM32F303xB STM32F303xC https://www.st.com/resource/en/datasheet/stm32f303cb.pdf + STM32F303x6/x8 https://www.st.com/resource/en/datasheet/stm32f303c6.pdf + STM32F334x4 STM32F334x6 STM32F334x8 https://www.st.com/resource/en/datasheet/stm32f334k4.pdf + STM32F373xx https://www.st.com/resource/en/datasheet/stm32f373cc.pdf + STM32F358xC https://www.st.com/resource/en/datasheet/stm32f358cc.pdf + STM32F378xx https://www.st.com/resource/en/datasheet/stm32f378cc.pdf + STM32F318C8 STM32F318K8 https://www.st.com/resource/en/datasheet/stm32f318c8.pdf + STM32F328C8 https://www.st.com/resource/en/datasheet/stm32f328c8.pdf + STM32F398VE https://www.st.com/resource/en/datasheet/stm32f398ve.pdf + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FFFF7B8 + #define TS_CAL2_TEMP 110 + #define TS_CAL2_REGOFFSET 0x1FFFF7C2 + +#elif defined(STM32F4xx) + /* + STM32F401xD STM32F401xE https://www.st.com/resource/en/datasheet/stm32f401re.pdf + STM32F411xC STM32F411xE https://www.st.com/resource/en/datasheet/stm32f411ce.pdf + STM32F446xC/E https://www.st.com/resource/en/datasheet/stm32f446mc.pdf + STM32F479xx https://www.st.com/resource/en/datasheet/stm32f479ai.pdf + STM32F412xE STM32F412xG https://www.st.com/resource/en/datasheet/stm32f412ce.pdf + STM32F410x8 STM32F410xB https://www.st.com/resource/en/datasheet/stm32f410cb.pdf + STM32F469xx https://www.st.com/resource/en/datasheet/stm32f469ae.pdf + STM32F423xH https://www.st.com/resource/en/datasheet/stm32f423ch.pdf + STM32F413xG STM32F413xH https://www.st.com/resource/en/datasheet/stm32f413cg.pdf + STM32F415xx STM32F417xx https://www.st.com/resource/en/datasheet/stm32f415rg.pdf + STM32F405xx STM32F407xx https://www.st.com/resource/en/datasheet/stm32f405rg.pdf + STM32F427xx STM32F429xx https://www.st.com/resource/en/datasheet/stm32f427vg.pdf + STM32F437xx STM32F439xx https://www.st.com/resource/en/datasheet/stm32f437vg.pdf + STM32F401xB STM32F401xC https://www.st.com/resource/en/datasheet/stm32f401cb.pdf + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FFF7A2C + #define TS_CAL2_TEMP 110 + #define TS_CAL2_REGOFFSET 0x1FFF7A2E + +#elif defined(STM32F7xx) + /* + STM32F756xx https://www.st.com/resource/en/datasheet/stm32f756bg.pdf + STM32F745xx STM32F746xx https://www.st.com/resource/en/datasheet/stm32f745ie.pdf + STM32F777xx STM32F778Ax STM32F779xx https://www.st.com/resource/en/datasheet/stm32f777bi.pdf + STM32F765xx STM32F767xx STM32F768Ax STM32F769xx https://www.st.com/resource/en/datasheet/stm32f765bi.pdf + STM32F722xx STM32F723xx https://www.st.com/resource/en/datasheet/stm32f722ic.pdf + --> TS_CAL1/2 = 0x1FF07A2C / 0x1FF07A2E + STM32F732xx STM32F733xx https://www.st.com/resource/en/datasheet/stm32f732ie.pdf + --> TS_CAL1/2 = 0x1FF07A2C / 0x1FF07A2E + STM32F750x8 https://www.st.com/resource/en/datasheet/stm32f750n8.pdf + STM32F730x8 https://www.st.com/resource/en/datasheet/stm32f730i8.pdf + --> TS_CAL1/2 = 0x1FF07A2C / 0x1FF07A2E + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FF0F44C + #define TS_CAL2_TEMP 110 + #define TS_CAL2_REGOFFSET 0x1FF0F44E + +#elif defined(STM32G0xx) + /* + STM32G030x6/x8 https://www.st.com/resource/en/datasheet/stm32g030c6.pdf + --> TS_CAL2 not defined in datasheet + STM32G050x6/x8 https://www.st.com/resource/en/datasheet/stm32g050c6.pdf + STM32G0B0KE/CE/RE/VE https://www.st.com/resource/en/datasheet/stm32g0b0ce.pdf + --> TS_CAL2 not defined in datasheet + STM32G081xB https://www.st.com/resource/en/datasheet/stm32g081cb.pdf + STM32G071x8/xB https://www.st.com/resource/en/datasheet/stm32g071c8.pdf + STM32G031x4/x6/x8 https://www.st.com/resource/en/datasheet/stm32g031c6.pdf + STM32G041x6/x8 https://www.st.com/resource/en/datasheet/stm32g041c8.pdf + STM32G051x6/x8 https://www.st.com/resource/en/datasheet/stm32g051c6.pdf + STM32G061x6/x8 https://www.st.com/resource/en/datasheet/stm32g061c6.pdf + STM32G0B1xB/xC/xE https://www.st.com/resource/en/datasheet/stm32g0b1cc.pdf + STM32G0C1xC/xE https://www.st.com/resource/en/datasheet/stm32g0c1cc.pdf + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FFF75A8 + #define TS_CAL2_TEMP 130 + #define TS_CAL2_REGOFFSET 0x1FFF75CA + +#elif defined(STM32G4xx) + /* + STM32G431x6 STM32G431x8 STM32G431xB https://www.st.com/resource/en/datasheet/stm32g431c6.pdf + STM32G441xB https://www.st.com/resource/en/datasheet/stm32g441cb.pdf + STM32G491xC STM32G491xE https://www.st.com/resource/en/datasheet/stm32g491cc.pdf + STM32G4A1xE https://www.st.com/resource/en/datasheet/stm32g4a1ce.pdf + STM32G473xB STM32G473xC STM32G473xE https://www.st.com/resource/en/datasheet/stm32g473cb.pdf + STM32G483xE https://www.st.com/resource/en/datasheet/stm32g483ce.pdf + --> TS_CAL1/TS_CAL2 not defined in datasheet + STM32G474xB STM32G474xC STM32G474xE https://www.st.com/resource/en/datasheet/stm32g474cb.pdf + STM32G484xE https://www.st.com/resource/en/datasheet/stm32g484ce.pdf + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FFF75A8 + #define TS_CAL2_TEMP 130 + #define TS_CAL2_REGOFFSET 0x1FFF75CA + +#elif defined(STM32H7xx) + /* + STM32H7A3xI/G + --> TS_CAL1/2 = 0x08FFF814 / 0x08FFF818 + STM32H7B0xB + --> TS_CAL1/2 = 0x08FFF814 / 0x08FFF818 + STM32H7B3xI + --> TS_CAL1/2 = 0x08FFF814 / 0x08FFF818 + STM32H725xE/G + STM32H735xG + STM32H723VE STM32H723VG STM32H723ZE STM32H723ZG + STM32H730AB STM32H730IB STM32H730VB STM32H730ZB + STM32H733VG STM32H733ZG + STM32H742xI/G STM32H743xI/G + --> CAL2_TEMP = 110 + STM32H745xI/G + STM32H747xI/G + STM32H753xI + STM32H755xI + STM32H757xI + STM32H750VB STM32H750ZB STM32H750IB STM32H750XB + --> CAL2_TEMP = 110 + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FF1E820 + #define TS_CAL2_TEMP 130 + #define TS_CAL2_REGOFFSET 0x1FF1E840 + +#elif defined(STM32L0xx) + /* + STM32L010RB + --> TS_CAL1/TS_CAL2 not defined in datasheet + STM32L010F4 STM32L010K4 + --> TS_CAL1/TS_CAL2 not defined in datasheet + STM32L010C6 + --> TS_CAL1/TS_CAL2 not defined in datasheet + STM32L010K8 STM32L010R8 + --> TS_CAL1/TS_CAL2 not defined in datasheet + STM32L011x3 STM32L011x4 + --> TS_CAL1 not defined in datasheet + STM32L021D4 STM32L021F4 STM32L021G4 STM32L021K4 + --> TS_CAL1 not defined in datasheet + STM32L031x4 STM32L031x6 + STM32L041x6 + STM32L051x6 STM32L051x8 + STM32L071x8 STM32L071xB STM32L071xZ + STM32L081CB STM32L081CZ STM32L081KZ + STM32L052x6 STM32L052x8 + STM32L062K8 STM32L062T8 STM32L062C8 + STM32L072x8 STM32L072xB STM32L072xZ + STM32L082KB STM32L082KZ STM32L082CZ + STM32L053C6 STM32L053C8 STM32L053R6 STM32L053R8 + STM32L063C8 STM32L063R8 + STM32L073x8 STM32L073xB STM32L073xZ + STM32L083x8 STM32L083xB STM32L083xZ + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FF8007A + #define TS_CAL2_TEMP 130 + #define TS_CAL2_REGOFFSET 0x1FF8007E + +#elif defined(STM32L1xx) + /* + STM32L100x6/8/B-A + --> TS_CAL1/TS_CAL2 not defined in datasheet + STM32L100RC + --> TS_CAL1/TS_CAL2 not defined in datasheet + STM32L100C6 STM32L100R8/RB + --> TS_CAL1/TS_CAL2 not defined in datasheet + STM32L151x6/8/B-A STM32L152x6/8/B-A + --> TS_CAL1/2 = 0x08FFF814 / 0x08FFF818 + STM32L151xD STM32L152xD + STM32L151VD-X STM32L152VD-X + STM32L15xCC STM32L15xRC STM32L15xUC STM32L15xVC + STM32L15xQC STM32L15xRC-A STM32L15xVC-A STM32L15xZC + STM32L162xE + STM32L162VD STM32L162ZD STM32L162QD STM32L162RD + STM32L162VC STM32L162RC + STM32L162VD-X + STM32L162QC STM32L162VC-A STM32L162ZC STM32L162RC-A + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FF800FA + #define TS_CAL2_TEMP 110 + #define TS_CAL2_REGOFFSET 0x1FF800FE + +#elif defined(STM32L4xx) + /* + STM32L431xx + STM32L451xx + STM32L471xx + --> CAL2_TEMP = 110 + STM32L412xx + STM32L422xx + STM32L432KB STM32L432KC + STM32L442KC + STM32L452xx + STM32L462CE STM32L462RE STM32L462VE + STM32L433xx + STM32L443CC STM32L443RC STM32L443VC + STM32L475xx + --> CAL2_TEMP = 110 + STM32L476xx + --> CAL2_TEMP = 110 + STM32L486xx : + --> CAL2_TEMP = 110 + STM32L496xx + STM32L4A6xG + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FFF75A8 + #define TS_CAL2_TEMP 130 + #define TS_CAL2_REGOFFSET 0x1FFF75CA + +#elif defined(STM32MP1xx) + /* + STM32MP131A STM32MP131D + STM32MP131C STM32MP131F + STM32MP133A STM32MP133D + STM32MP133C STM32MP133F + STM32MP135A STM32MP135D + STM32MP135C STM32MP135F + STM32MP151A/D + STM32MP151C/F + STM32MP153A/D + STM32MP153C/F + STM32MP157A/D + STM32MP157C/F + */ + // BSEC -> RCC + //#define TS_CAL1_TEMP 30 + //#define TS_CAL1_REGOFFSET 0x5C00 525C[15:0] + //#define TS_CAL2_TEMP 130 + //#define TS_CAL2_REGOFFSET 0x5C00 525C[31:16] + +#elif defined(STM32WBxx) + /* + STM32WB10CC + STM32WB50CG STM32WB30CE + STM32WB15CC + STM32WB55xx STM32WB35xx + */ + #define TS_CAL1_TEMP 30 + #define TS_CAL1_REGOFFSET 0x1FFF75A8 + #define TS_CAL2_TEMP 130 + #define TS_CAL2_REGOFFSET 0x1FFF75CA +#endif + +// TODO implement voltage scaling (calibrated Vrefint) and ADC resolution scaling (when applicable) + +/** + * When provided in datasheet, the use of calibrated values (TS_CAL1, TS_CAL2) should always be preferred over typical values. + * Typical values may result in important variation from the actual temperature. + * + * If calibrated values are not provided in datasheet, it is encouraged to calibrate your specific chip yourself. + */ +#if defined(TS_CAL1_TEMP) && defined(TS_CAL1_REGOFFSET) && defined(TS_CAL2_TEMP) && defined(TS_CAL2_REGOFFSET) + + #define READMEMORY(ADDR) (*((uint16_t const *)(ADDR))) + #define TEMP_SOC_SENSOR(RAW) (float((TS_CAL2_TEMP) - (TS_CAL1_TEMP)) / (READMEMORY(TS_CAL2_REGOFFSET) - READMEMORY(TS_CAL1_REGOFFSET)) * ((RAW) / float(OVERSAMPLENR) - READMEMORY(TS_CAL1_REGOFFSET)) + (TS_CAL1_TEMP)) + +#elif defined(TS_TYPICAL_V) && defined(TS_TYPICAL_SLOPE) && defined(TS_TYPICAL_TEMP) + + #define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000.0f)) / ((TS_TYPICAL_SLOPE) / 1000.0f) + TS_TYPICAL_TEMP) + +#endif diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp index 180abc68b0..e57bccfef3 100644 --- a/Marlin/src/HAL/STM32/tft/gt911.cpp +++ b/Marlin/src/HAL/STM32/tft/gt911.cpp @@ -90,7 +90,7 @@ bool SW_IIC::read_ack() { } void SW_IIC::send_byte(uint8_t txd) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { write_sda(txd & 0x80); // write data bit txd <<= 1; iic_delay(1); @@ -107,7 +107,7 @@ uint8_t SW_IIC::read_byte(bool ack) { uint8_t data = 0; set_sda_in(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { write_scl(HIGH); // SCL = 1 iic_delay(1); data <<= 1; @@ -128,12 +128,12 @@ SW_IIC GT911::sw_iic = SW_IIC(GT911_SW_I2C_SDA_PIN, GT911_SW_I2C_SCL_PIN); void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len) { sw_iic.start(); sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address - LOOP_L_N(i, reg_len) { // Set reg address + for (uint8_t i = 0; i < reg_len; ++i) { // Set reg address uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; sw_iic.send_byte(r); } - LOOP_L_N(i, w_len) { // Write data to reg + for (uint8_t i = 0; i < w_len; ++i) { // Write data to reg sw_iic.send_byte(w_data[i]); } sw_iic.stop(); @@ -142,7 +142,7 @@ void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len) { sw_iic.start(); sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address - LOOP_L_N(i, reg_len) { // Set reg address + for (uint8_t i = 0; i < reg_len; ++i) { // Set reg address uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; sw_iic.send_byte(r); } @@ -150,13 +150,13 @@ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_l sw_iic.start(); sw_iic.send_byte(gt911_slave_address + 1); // Set read mode - LOOP_L_N(i, r_len) { + for (uint8_t i = 0; i < r_len; ++i) r_data[i] = sw_iic.read_byte(1); // Read data from reg - } + sw_iic.stop(); } -void GT911::Init() { +void GT911::init() { OUT_WRITE(GT911_RST_PIN, LOW); OUT_WRITE(GT911_INT_PIN, LOW); delay(11); @@ -189,8 +189,8 @@ bool GT911::getFirstTouchPoint(int16_t *x, int16_t *y) { return false; } -bool GT911::getPoint(int16_t *x, int16_t *y) { - static bool touched = 0; +bool GT911::getRawPoint(int16_t * const x, int16_t * const y) { + static bool touched = false; static int16_t read_x = 0, read_y = 0; static millis_t next_time = 0; diff --git a/Marlin/src/HAL/STM32/tft/gt911.h b/Marlin/src/HAL/STM32/tft/gt911.h index 6ecfe8b82e..989517c183 100644 --- a/Marlin/src/HAL/STM32/tft/gt911.h +++ b/Marlin/src/HAL/STM32/tft/gt911.h @@ -39,42 +39,18 @@ class SW_IIC { private: uint16_t scl_pin; uint16_t sda_pin; - void write_scl(bool level) - { - WRITE(scl_pin, level); - } - void write_sda(bool level) - { - WRITE(sda_pin, level); - } - bool read_sda() - { - return READ(sda_pin); - } - void set_sda_out() - { - SET_OUTPUT(sda_pin); - } - void set_sda_in() - { - SET_INPUT_PULLUP(sda_pin); - } - static void iic_delay(uint8_t t) - { - delayMicroseconds(t); - } + void write_scl(bool level) { WRITE(scl_pin, level); } + void write_sda(bool level) { WRITE(sda_pin, level); } + bool read_sda() { return READ(sda_pin); } + void set_sda_out() { SET_OUTPUT(sda_pin); } + void set_sda_in() { SET_INPUT_PULLUP(sda_pin); } + static void iic_delay(uint8_t t) { delayMicroseconds(t); } public: SW_IIC(uint16_t sda, uint16_t scl); // setSCL/SDA have to be called before begin() - void setSCL(uint16_t scl) - { - scl_pin = scl; - }; - void setSDA(uint16_t sda) - { - sda_pin = sda; - }; + void setSCL(uint16_t scl) { scl_pin = scl; } + void setSDA(uint16_t sda) { sda_pin = sda; } void init(); // Initialize the IO port of IIC void start(); // Send IIC start signal void stop(); // Send IIC stop signal @@ -114,7 +90,7 @@ class GT911 { static void read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len); public: - static void Init(); + static void init(); static bool getFirstTouchPoint(int16_t *x, int16_t *y); - static bool getPoint(int16_t *x, int16_t *y); + static bool getRawPoint(int16_t * const x, int16_t * const y); }; diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index e68b3c1269..70caef6778 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -35,139 +35,170 @@ SRAM_HandleTypeDef TFT_FSMC::SRAMx; DMA_HandleTypeDef TFT_FSMC::DMAtx; LCD_CONTROLLER_TypeDef *TFT_FSMC::LCD; -void TFT_FSMC::Init() { +void TFT_FSMC::init() { uint32_t controllerAddress; - FSMC_NORSRAM_TimingTypeDef Timing, ExtTiming; + FMC_OR_FSMC(NORSRAM_TimingTypeDef) timing, extTiming; - uint32_t NSBank = (uint32_t)pinmap_peripheral(digitalPinToPinName(TFT_CS_PIN), PinMap_FSMC_CS); + uint32_t nsBank = (uint32_t)pinmap_peripheral(digitalPinToPinName(TFT_CS_PIN), pinMap_FSMC_CS); // Perform the SRAM1 memory initialization sequence - SRAMx.Instance = FSMC_NORSRAM_DEVICE; - SRAMx.Extended = FSMC_NORSRAM_EXTENDED_DEVICE; + SRAMx.Instance = FMC_OR_FSMC(NORSRAM_DEVICE); + SRAMx.Extended = FMC_OR_FSMC(NORSRAM_EXTENDED_DEVICE); + // SRAMx.Init - SRAMx.Init.NSBank = NSBank; - SRAMx.Init.DataAddressMux = FSMC_DATA_ADDRESS_MUX_DISABLE; - SRAMx.Init.MemoryType = FSMC_MEMORY_TYPE_SRAM; - SRAMx.Init.MemoryDataWidth = TERN(TFT_INTERFACE_FSMC_8BIT, FSMC_NORSRAM_MEM_BUS_WIDTH_8, FSMC_NORSRAM_MEM_BUS_WIDTH_16); - SRAMx.Init.BurstAccessMode = FSMC_BURST_ACCESS_MODE_DISABLE; - SRAMx.Init.WaitSignalPolarity = FSMC_WAIT_SIGNAL_POLARITY_LOW; - SRAMx.Init.WrapMode = FSMC_WRAP_MODE_DISABLE; - SRAMx.Init.WaitSignalActive = FSMC_WAIT_TIMING_BEFORE_WS; - SRAMx.Init.WriteOperation = FSMC_WRITE_OPERATION_ENABLE; - SRAMx.Init.WaitSignal = FSMC_WAIT_SIGNAL_DISABLE; - SRAMx.Init.ExtendedMode = FSMC_EXTENDED_MODE_ENABLE; - SRAMx.Init.AsynchronousWait = FSMC_ASYNCHRONOUS_WAIT_DISABLE; - SRAMx.Init.WriteBurst = FSMC_WRITE_BURST_DISABLE; - #ifdef STM32F4xx - SRAMx.Init.PageSize = FSMC_PAGE_SIZE_NONE; + SRAMx.Init.NSBank = nsBank; + SRAMx.Init.DataAddressMux = FMC_OR_FSMC(DATA_ADDRESS_MUX_DISABLE); + SRAMx.Init.MemoryType = FMC_OR_FSMC(MEMORY_TYPE_SRAM); + #ifdef STM32F446xx + SRAMx.Init.MemoryDataWidth = TERN(TFT_INTERFACE_FMC_8BIT, FMC_NORSRAM_MEM_BUS_WIDTH_8, FMC_NORSRAM_MEM_BUS_WIDTH_16); + #else + SRAMx.Init.MemoryDataWidth = TERN(TFT_INTERFACE_FSMC_8BIT, FSMC_NORSRAM_MEM_BUS_WIDTH_8, FSMC_NORSRAM_MEM_BUS_WIDTH_16); #endif + SRAMx.Init.BurstAccessMode = FMC_OR_FSMC(BURST_ACCESS_MODE_DISABLE); + SRAMx.Init.WaitSignalPolarity = FMC_OR_FSMC(WAIT_SIGNAL_POLARITY_LOW); + SRAMx.Init.WrapMode = FMC_OR_FSMC(WRAP_MODE_DISABLE); + SRAMx.Init.WaitSignalActive = FMC_OR_FSMC(WAIT_TIMING_BEFORE_WS); + SRAMx.Init.WriteOperation = FMC_OR_FSMC(WRITE_OPERATION_ENABLE); + SRAMx.Init.WaitSignal = FMC_OR_FSMC(WAIT_SIGNAL_DISABLE); + SRAMx.Init.ExtendedMode = FMC_OR_FSMC(EXTENDED_MODE_ENABLE); + SRAMx.Init.AsynchronousWait = FMC_OR_FSMC(ASYNCHRONOUS_WAIT_DISABLE); + SRAMx.Init.WriteBurst = FMC_OR_FSMC(WRITE_BURST_DISABLE); + #if defined(STM32F446xx) || defined(STM32F4xx) + SRAMx.Init.PageSize = FMC_OR_FSMC(PAGE_SIZE_NONE); + #endif + // Read Timing - relatively slow to ensure ID information is correctly read from TFT controller - // Can be decreases from 15-15-24 to 4-4-8 with risk of stability loss - Timing.AddressSetupTime = 15; - Timing.AddressHoldTime = 15; - Timing.DataSetupTime = 24; - Timing.BusTurnAroundDuration = 0; - Timing.CLKDivision = 16; - Timing.DataLatency = 17; - Timing.AccessMode = FSMC_ACCESS_MODE_A; + // Can be decreased from 15-15-24 to 4-4-8 with risk of stability loss + timing.AddressSetupTime = 15; + timing.AddressHoldTime = 15; + timing.DataSetupTime = 24; + timing.BusTurnAroundDuration = 0; + timing.CLKDivision = 16; + timing.DataLatency = 17; + timing.AccessMode = FMC_OR_FSMC(ACCESS_MODE_A); + // Write Timing - // Can be decreases from 8-15-8 to 0-0-1 with risk of stability loss - ExtTiming.AddressSetupTime = 8; - ExtTiming.AddressHoldTime = 15; - ExtTiming.DataSetupTime = 8; - ExtTiming.BusTurnAroundDuration = 0; - ExtTiming.CLKDivision = 16; - ExtTiming.DataLatency = 17; - ExtTiming.AccessMode = FSMC_ACCESS_MODE_A; + // Can be decreased from 8-15-8 to 0-0-1 with risk of stability loss + extTiming.AddressSetupTime = 8; + extTiming.AddressHoldTime = 15; + extTiming.DataSetupTime = 8; + extTiming.BusTurnAroundDuration = 0; + extTiming.CLKDivision = 16; + extTiming.DataLatency = 17; + extTiming.AccessMode = FMC_OR_FSMC(ACCESS_MODE_A); - __HAL_RCC_FSMC_CLK_ENABLE(); + #ifdef STM32F446xx + __HAL_RCC_FMC_CLK_ENABLE(); + #else + __HAL_RCC_FSMC_CLK_ENABLE(); + #endif - for (uint16_t i = 0; PinMap_FSMC[i].pin != NC; i++) - pinmap_pinout(PinMap_FSMC[i].pin, PinMap_FSMC); - pinmap_pinout(digitalPinToPinName(TFT_CS_PIN), PinMap_FSMC_CS); - pinmap_pinout(digitalPinToPinName(TFT_RS_PIN), PinMap_FSMC_RS); + for (uint16_t i = 0; pinMap_FSMC[i].pin != NC; i++) + pinmap_pinout(pinMap_FSMC[i].pin, pinMap_FSMC); + pinmap_pinout(digitalPinToPinName(TFT_CS_PIN), pinMap_FSMC_CS); + pinmap_pinout(digitalPinToPinName(TFT_RS_PIN), pinMap_FSMC_RS); controllerAddress = FSMC_BANK1_1; #ifdef PF0 - switch (NSBank) { - case FSMC_NORSRAM_BANK2: controllerAddress = FSMC_BANK1_2 ; break; - case FSMC_NORSRAM_BANK3: controllerAddress = FSMC_BANK1_3 ; break; - case FSMC_NORSRAM_BANK4: controllerAddress = FSMC_BANK1_4 ; break; + switch (nsBank) { + case FMC_OR_FSMC(NORSRAM_BANK2): controllerAddress = FSMC_BANK1_2; break; + case FMC_OR_FSMC(NORSRAM_BANK3): controllerAddress = FSMC_BANK1_3; break; + case FMC_OR_FSMC(NORSRAM_BANK4): controllerAddress = FSMC_BANK1_4; break; } #endif - controllerAddress |= (uint32_t)pinmap_peripheral(digitalPinToPinName(TFT_RS_PIN), PinMap_FSMC_RS); + controllerAddress |= (uint32_t)pinmap_peripheral(digitalPinToPinName(TFT_RS_PIN), pinMap_FSMC_RS); - HAL_SRAM_Init(&SRAMx, &Timing, &ExtTiming); + HAL_SRAM_Init(&SRAMx, &timing, &extTiming); __HAL_RCC_DMA2_CLK_ENABLE(); #ifdef STM32F1xx - DMAtx.Instance = DMA2_Channel1; + DMAtx.Instance = DMA2_Channel1; #elif defined(STM32F4xx) - DMAtx.Instance = DMA2_Stream0; - DMAtx.Init.Channel = DMA_CHANNEL_0; - DMAtx.Init.FIFOMode = DMA_FIFOMODE_ENABLE; - DMAtx.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; - DMAtx.Init.MemBurst = DMA_MBURST_SINGLE; - DMAtx.Init.PeriphBurst = DMA_PBURST_SINGLE; + DMAtx.Instance = DMA2_Stream0; + DMAtx.Init.Channel = DMA_CHANNEL_0; + DMAtx.Init.FIFOMode = DMA_FIFOMODE_ENABLE; + DMAtx.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + DMAtx.Init.MemBurst = DMA_MBURST_SINGLE; + DMAtx.Init.PeriphBurst = DMA_PBURST_SINGLE; #endif - DMAtx.Init.Direction = DMA_MEMORY_TO_MEMORY; - DMAtx.Init.MemInc = DMA_MINC_DISABLE; - DMAtx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; - DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; - DMAtx.Init.Mode = DMA_NORMAL; - DMAtx.Init.Priority = DMA_PRIORITY_HIGH; + DMAtx.Init.Direction = DMA_MEMORY_TO_MEMORY; + DMAtx.Init.MemInc = DMA_MINC_DISABLE; + DMAtx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; + DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + DMAtx.Init.Mode = DMA_NORMAL; + DMAtx.Init.Priority = DMA_PRIORITY_HIGH; LCD = (LCD_CONTROLLER_TypeDef *)controllerAddress; + + DMAtx.Init.PeriphInc = DMA_PINC_DISABLE; + HAL_DMA_Init(&DMAtx); } -uint32_t TFT_FSMC::GetID() { - uint32_t id; - WriteReg(0); - id = LCD->RAM; - - if (id == 0) - id = ReadID(LCD_READ_ID); - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) - id = ReadID(LCD_READ_ID4); +uint32_t TFT_FSMC::getID() { + writeReg(0); + uint32_t id = LCD->RAM; + if (id == 0) id = readID(LCD_READ_ID); + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) id = readID(LCD_READ_ID4); return id; } -uint32_t TFT_FSMC::ReadID(tft_data_t Reg) { - uint32_t id; - WriteReg(Reg); - id = LCD->RAM; // dummy read - id = Reg << 24; +uint32_t TFT_FSMC::readID(tft_data_t inReg) { + writeReg(inReg); + uint32_t id = LCD->RAM; // dummy read + id = inReg << 24; id |= (LCD->RAM & 0x00FF) << 16; id |= (LCD->RAM & 0x00FF) << 8; - id |= LCD->RAM & 0x00FF; + id |= (LCD->RAM & 0x00FF); return id; } bool TFT_FSMC::isBusy() { - #if defined(STM32F1xx) - volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET; + #ifdef STM32F1xx + #define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CCR & DMA_CCR_EN) + #define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->Instance->CPAR != 0) #elif defined(STM32F4xx) - volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN; + #define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR & DMA_SxCR_EN) + #define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->Instance->PAR != 0) #endif - if (dmaEnabled) { - if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) - Abort(); - } - else - Abort(); - return dmaEnabled; + + #ifdef __IS_DMA_CONFIGURED + if (!__IS_DMA_CONFIGURED(&DMAtx)) return false; + #endif + + // Check if DMA transfer error or transfer complete flags are set + if ((__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) == 0) && (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) == 0)) return true; + + __DSB(); + abort(); + return false; } -void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - DMAtx.Init.PeriphInc = MemoryIncrease; - HAL_DMA_Init(&DMAtx); - DataTransferBegin(); - HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(LCD->RAM), Count); +void TFT_FSMC::abort() { + HAL_DMA_Abort(&DMAtx); // Abort DMA transfer if any + HAL_DMA_DeInit(&DMAtx); // Deconfigure DMA +} + +void TFT_FSMC::transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + if (!__IS_DMA_CONFIGURED(&DMAtx) || DMAtx.Init.PeriphInc != memoryIncrease) { + DMAtx.Init.PeriphInc = memoryIncrease; + HAL_DMA_Init(&DMAtx); + } + HAL_DMA_Start(&DMAtx, (uint32_t)data, (uint32_t)&(LCD->RAM), count); + TERN_(TFT_SHARED_IO, while (isBusy())); +} + +void TFT_FSMC::transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + if (!__IS_DMA_CONFIGURED(&DMAtx) || DMAtx.Init.PeriphInc != memoryIncrease) { + DMAtx.Init.PeriphInc = memoryIncrease; + HAL_DMA_Init(&DMAtx); + } + dataTransferBegin(); + HAL_DMA_Start(&DMAtx, (uint32_t)data, (uint32_t)&(LCD->RAM), count); HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); - Abort(); + abort(); } #endif // HAS_FSMC_TFT diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.h b/Marlin/src/HAL/STM32/tft/tft_fsmc.h index 2200abaa10..2647923e8e 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.h @@ -28,7 +28,7 @@ #elif defined(STM32F4xx) #include "stm32f4xx_hal.h" #else - #error "FSMC TFT is currently only supported on STM32F1 and STM32F4 hardware." + #error "FSMC/FMC TFT is currently only supported on STM32F1 and STM32F4 hardware." #endif #ifndef LCD_READ_ID @@ -41,6 +41,7 @@ #define DATASIZE_8BIT SPI_DATASIZE_8BIT #define DATASIZE_16BIT SPI_DATASIZE_16BIT #define TFT_IO_DRIVER TFT_FSMC +#define DMA_MAX_WORDS 0xFFFF #define TFT_DATASIZE TERN(TFT_INTERFACE_FSMC_8BIT, DATASIZE_8BIT, DATASIZE_16BIT) typedef TERN(TFT_INTERFACE_FSMC_8BIT, uint8_t, uint16_t) tft_data_t; @@ -50,6 +51,12 @@ typedef struct { __IO tft_data_t RAM; } LCD_CONTROLLER_TypeDef; +#ifdef STM32F446xx + #define FMC_OR_FSMC(N) _CAT(FMC_, N) +#else + #define FMC_OR_FSMC(N) _CAT(FSMC_, N) +#endif + class TFT_FSMC { private: static SRAM_HandleTypeDef SRAMx; @@ -57,29 +64,31 @@ class TFT_FSMC { static LCD_CONTROLLER_TypeDef *LCD; - static uint32_t ReadID(tft_data_t Reg); - static void Transmit(tft_data_t Data) { LCD->RAM = Data; __DSB(); } - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static uint32_t readID(tft_data_t inReg); + static void transmit(tft_data_t data) { LCD->RAM = data; __DSB(); } + static void transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count); + static void transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count); public: - static void Init(); - static uint32_t GetID(); + static void init(); + static uint32_t getID(); static bool isBusy(); - static void Abort() { __HAL_DMA_DISABLE(&DMAtx); } + static void abort(); - static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {} - static void DataTransferEnd() {}; + static void dataTransferBegin(uint16_t dataWidth=TFT_DATASIZE) {} + static void dataTransferEnd() {} - static void WriteData(uint16_t Data) { Transmit(tft_data_t(Data)); } - static void WriteReg(uint16_t Reg) { LCD->REG = tft_data_t(Reg); __DSB(); } + static void writeData(uint16_t data) { transmit(tft_data_t(data)); } + static void writeReg(const uint16_t inReg) { LCD->REG = tft_data_t(inReg); __DSB(); } - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); } - static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; - while (Count > 0) { - TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); - Count = Count > 0xFFFF ? Count - 0xFFFF : 0; + static void writeSequence_DMA(uint16_t *data, uint16_t count) { transmitDMA(DMA_PINC_ENABLE, data, count); } + static void writeMultiple_DMA(uint16_t color, uint16_t count) { static uint16_t data; data = color; transmitDMA(DMA_PINC_DISABLE, &data, count); } + + static void writeSequence(uint16_t *data, uint16_t count) { transmit(DMA_PINC_ENABLE, data, count); } + static void writeMultiple(uint16_t color, uint32_t count) { + while (count > 0) { + transmit(DMA_MINC_DISABLE, &color, count > DMA_MAX_WORDS ? DMA_MAX_WORDS : count); + count = count > DMA_MAX_WORDS ? count - DMA_MAX_WORDS : 0; } } }; @@ -87,7 +96,11 @@ class TFT_FSMC { #ifdef STM32F1xx #define FSMC_PIN_DATA STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE) #elif defined(STM32F4xx) - #define FSMC_PIN_DATA STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_FSMC) + #ifdef STM32F446xx + #define FSMC_PIN_DATA STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_FMC) + #else + #define FSMC_PIN_DATA STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_FSMC) + #endif #define FSMC_BANK1_1 0x60000000U #define FSMC_BANK1_2 0x64000000U #define FSMC_BANK1_3 0x68000000U @@ -96,36 +109,36 @@ class TFT_FSMC { #error No configuration for this MCU #endif -const PinMap PinMap_FSMC[] = { - {PD_14, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D00 - {PD_15, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D01 - {PD_0, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D02 - {PD_1, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D03 - {PE_7, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D04 - {PE_8, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D05 - {PE_9, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D06 - {PE_10, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D07 +const PinMap pinMap_FSMC[] = { + {PD_14, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D00 + {PD_15, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D01 + {PD_0, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D02 + {PD_1, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D03 + {PE_7, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D04 + {PE_8, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D05 + {PE_9, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D06 + {PE_10, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D07 #if DISABLED(TFT_INTERFACE_FSMC_8BIT) - {PE_11, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D08 - {PE_12, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D09 - {PE_13, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D10 - {PE_14, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D11 - {PE_15, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D12 - {PD_8, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D13 - {PD_9, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D14 - {PD_10, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D15 + {PE_11, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D08 + {PE_12, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D09 + {PE_13, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D10 + {PE_14, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D11 + {PE_15, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D12 + {PD_8, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D13 + {PD_9, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D14 + {PD_10, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_D15 #endif - {PD_4, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_NOE - {PD_5, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_NWE + {PD_4, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_NOE + {PD_5, FMC_OR_FSMC(NORSRAM_DEVICE), FSMC_PIN_DATA}, // FSMC_NWE {NC, NP, 0} }; -const PinMap PinMap_FSMC_CS[] = { - {PD_7, (void *)FSMC_NORSRAM_BANK1, FSMC_PIN_DATA}, // FSMC_NE1 +const PinMap pinMap_FSMC_CS[] = { + {PD_7, (void *)FMC_OR_FSMC(NORSRAM_BANK1), FSMC_PIN_DATA}, // FSMC_NE1 #ifdef PF0 - {PG_9, (void *)FSMC_NORSRAM_BANK2, FSMC_PIN_DATA}, // FSMC_NE2 - {PG_10, (void *)FSMC_NORSRAM_BANK3, FSMC_PIN_DATA}, // FSMC_NE3 - {PG_12, (void *)FSMC_NORSRAM_BANK4, FSMC_PIN_DATA}, // FSMC_NE4 + {PG_9, (void *)FMC_OR_FSMC(NORSRAM_BANK2), FSMC_PIN_DATA}, // FSMC_NE2 + {PG_10, (void *)FMC_OR_FSMC(NORSRAM_BANK3), FSMC_PIN_DATA}, // FSMC_NE3 + {PG_12, (void *)FMC_OR_FSMC(NORSRAM_BANK4), FSMC_PIN_DATA}, // FSMC_NE4 #endif {NC, NP, 0} }; @@ -136,7 +149,7 @@ const PinMap PinMap_FSMC_CS[] = { #define FSMC_RS(A) (void *)((2 << A) - 2) #endif -const PinMap PinMap_FSMC_RS[] = { +const PinMap pinMap_FSMC_RS[] = { #ifdef PF0 {PF_0, FSMC_RS( 0), FSMC_PIN_DATA}, // FSMC_A0 {PF_1, FSMC_RS( 1), FSMC_PIN_DATA}, // FSMC_A1 diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp index 95871bf41f..3bbc39f20a 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -246,28 +246,28 @@ uint16_t TFT_LTDC::y_cur = 0; uint8_t TFT_LTDC::reg = 0; volatile uint16_t* TFT_LTDC::framebuffer = (volatile uint16_t* )FRAME_BUFFER_ADDRESS; -void TFT_LTDC::Init() { +void TFT_LTDC::init() { // SDRAM pins init - for (uint16_t i = 0; PinMap_SDRAM[i].pin != NC; i++) - pinmap_pinout(PinMap_SDRAM[i].pin, PinMap_SDRAM); + for (uint16_t i = 0; pinMap_SDRAM[i].pin != NC; i++) + pinmap_pinout(pinMap_SDRAM[i].pin, pinMap_SDRAM); // SDRAM peripheral config SDRAM_Config(); // LTDC pins init - for (uint16_t i = 0; PinMap_LTDC[i].pin != NC; i++) - pinmap_pinout(PinMap_LTDC[i].pin, PinMap_LTDC); + for (uint16_t i = 0; pinMap_LTDC[i].pin != NC; i++) + pinmap_pinout(pinMap_LTDC[i].pin, pinMap_LTDC); // LTDC peripheral config LTDC_Config(); } -uint32_t TFT_LTDC::GetID() { +uint32_t TFT_LTDC::getID() { return 0xABAB; } -uint32_t TFT_LTDC::ReadID(tft_data_t Reg) { +uint32_t TFT_LTDC::readID(const tft_data_t inReg) { return 0xABAB; } @@ -275,15 +275,15 @@ bool TFT_LTDC::isBusy() { return false; } -uint16_t TFT_LTDC::ReadPoint(uint16_t x, uint16_t y) { +uint16_t TFT_LTDC::readPoint(uint16_t x, uint16_t y) { return framebuffer[(TFT_WIDTH * y) + x]; } -void TFT_LTDC::DrawPoint(uint16_t x, uint16_t y, uint16_t color) { +void TFT_LTDC::drawPoint(uint16_t x, uint16_t y, uint16_t color) { framebuffer[(TFT_WIDTH * y) + x] = color; } -void TFT_LTDC::DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color) { +void TFT_LTDC::drawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color) { if (sx == ex || sy == ey) return; @@ -307,7 +307,7 @@ void TFT_LTDC::DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint SBI(DMA2D->IFCR, 1); } -void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors) { +void TFT_LTDC::drawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors) { if (sx == ex || sy == ey) return; @@ -332,18 +332,18 @@ void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uin SBI(DMA2D->IFCR, 1); } -void TFT_LTDC::WriteData(uint16_t data) { +void TFT_LTDC::writeData(uint16_t data) { switch (reg) { case 0x01: x_cur = x_min = data; return; case 0x02: x_max = data; return; case 0x03: y_cur = y_min = data; return; case 0x04: y_max = data; return; } - Transmit(data); + transmit(data); } -void TFT_LTDC::Transmit(tft_data_t Data) { - DrawPoint(x_cur, y_cur, Data); +void TFT_LTDC::transmit(tft_data_t data) { + drawPoint(x_cur, y_cur, data); x_cur++; if (x_cur > x_max) { x_cur = x_min; @@ -352,35 +352,31 @@ void TFT_LTDC::Transmit(tft_data_t Data) { } } -void TFT_LTDC::WriteReg(uint16_t Reg) { - reg = Reg; -} +void TFT_LTDC::transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { -void TFT_LTDC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - - while (x_cur != x_min && Count) { - Transmit(*Data); - if (MemoryIncrease == DMA_PINC_ENABLE) Data++; - Count--; + while (x_cur != x_min && count) { + transmit(*data); + if (memoryIncrease == DMA_PINC_ENABLE) data++; + count--; } uint16_t width = x_max - x_min + 1; - uint16_t height = Count / width; - uint16_t x_end_cnt = Count - (width * height); + uint16_t height = count / width; + uint16_t x_end_cnt = count - (width * height); if (height) { - if (MemoryIncrease == DMA_PINC_ENABLE) { - DrawImage(x_min, y_cur, x_min + width, y_cur + height, Data); - Data += width * height; + if (memoryIncrease == DMA_PINC_ENABLE) { + drawImage(x_min, y_cur, x_min + width, y_cur + height, data); + data += width * height; } else - DrawRect(x_min, y_cur, x_min + width, y_cur + height, *Data); + drawRect(x_min, y_cur, x_min + width, y_cur + height, *data); y_cur += height; } while (x_end_cnt) { - Transmit(*Data); - if (MemoryIncrease == DMA_PINC_ENABLE) Data++; + transmit(*data); + if (memoryIncrease == DMA_PINC_ENABLE) data++; x_end_cnt--; } } diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.h b/Marlin/src/HAL/STM32/tft/tft_ltdc.h index 7b63d6929b..90cc58d8a5 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.h +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.h @@ -32,6 +32,7 @@ #define DATASIZE_8BIT SPI_DATASIZE_8BIT #define DATASIZE_16BIT SPI_DATASIZE_16BIT #define TFT_IO_DRIVER TFT_LTDC +#define DMA_MAX_WORDS 0xFFFF #define TFT_DATASIZE DATASIZE_16BIT typedef uint16_t tft_data_t; @@ -42,39 +43,41 @@ class TFT_LTDC { static uint16_t x_min, x_max, y_min, y_max, x_cur, y_cur; static uint8_t reg; - static uint32_t ReadID(tft_data_t Reg); + static uint32_t readID(const tft_data_t inReg); - static uint16_t ReadPoint(uint16_t x, uint16_t y); - static void DrawPoint(uint16_t x, uint16_t y, uint16_t color); - static void DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color); - static void DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors); - static void Transmit(tft_data_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static uint16_t readPoint(uint16_t x, uint16_t y); + static void drawPoint(uint16_t x, uint16_t y, uint16_t color); + static void drawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color); + static void drawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors); + static void transmit(tft_data_t data); + static void transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count); public: - static void Init(); - static uint32_t GetID(); + static void init(); + static uint32_t getID(); static bool isBusy(); - static void Abort() { /*__HAL_DMA_DISABLE(&DMAtx);*/ } + static void abort() { /*__HAL_DMA_DISABLE(&DMAtx);*/ } - static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {} - static void DataTransferEnd() {}; + static void dataTransferBegin(uint16_t dataWidth=TFT_DATASIZE) {} + static void dataTransferEnd() {}; - static void WriteData(uint16_t Data); - static void WriteReg(uint16_t Reg); + static void writeData(uint16_t data); + static void writeReg(const uint16_t inReg) { reg = inReg; } - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); } - static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; - while (Count > 0) { - TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); - Count = Count > 0xFFFF ? Count - 0xFFFF : 0; + // Non-blocking DMA data transfer is not implemented for LTDC interface + inline static void writeSequence_DMA(uint16_t *data, uint16_t count) { writeSequence(data, count); } + inline static void writeMultiple_DMA(uint16_t color, uint16_t count) { writeMultiple(color, count); } + + static void writeSequence(uint16_t *data, uint16_t count) { transmit(DMA_PINC_ENABLE, data, count); } + static void writeMultiple(uint16_t color, uint32_t count) { + while (count > 0) { + transmit(DMA_PINC_DISABLE, &color, count > DMA_MAX_WORDS ? DMA_MAX_WORDS : count); + count = count > DMA_MAX_WORDS ? count - DMA_MAX_WORDS : 0; } } }; -const PinMap PinMap_LTDC[] = { +const PinMap pinMap_LTDC[] = { {PF_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_DE {PG_7, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_CLK {PI_9, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_VSYNC @@ -101,7 +104,7 @@ const PinMap PinMap_LTDC[] = { {NC, NP, 0} }; -const PinMap PinMap_SDRAM[] = { +const PinMap pinMap_SDRAM[] = { {PC_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNWE {PC_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNE0 {PC_3, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDCKE0 diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 2e18c8a64c..71ad14534f 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -31,10 +31,14 @@ #include "tft_spi.h" #include "pinconfig.h" +//#define DEBUG_TFT_IO +#define DEBUG_OUT ENABLED(DEBUG_TFT_IO) +#include "../../../core/debug_out.h" + SPI_HandleTypeDef TFT_SPI::SPIx; DMA_HandleTypeDef TFT_SPI::DMAtx; -void TFT_SPI::Init() { +void TFT_SPI::init() { SPI_TypeDef *spiInstance; OUT_WRITE(TFT_A0_PIN, HIGH); @@ -43,8 +47,9 @@ void TFT_SPI::Init() { if ((spiInstance = (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK)) == NP) return; if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI)) return; - #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN - if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO)) return; + #if PIN_EXISTS(TFT_MISO) + // Check these pins in code because they are sometimes defined as analog pin references + if ((TFT_MISO_PIN != TFT_MOSI_PIN) && (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO))) return; #endif SPIx.Instance = spiInstance; @@ -52,7 +57,6 @@ void TFT_SPI::Init() { SPIx.Init.NSS = SPI_NSS_SOFT; SPIx.Init.Mode = SPI_MODE_MASTER; SPIx.Init.Direction = (TFT_MISO_PIN == TFT_MOSI_PIN) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES; - SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; SPIx.Init.CLKPhase = SPI_PHASE_1EDGE; SPIx.Init.CLKPolarity = SPI_POLARITY_LOW; SPIx.Init.DataSize = SPI_DATASIZE_8BIT; @@ -61,12 +65,28 @@ void TFT_SPI::Init() { SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; SPIx.Init.CRCPolynomial = 10; + #ifndef STM32H7xx + SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; // 18 MBit/s for F103, 21 MBit/s for F407, 25 MBit/s for F411 + #else + SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4; // 20 MBit/s for H743 + SPIx.Init.NSSPMode = SPI_NSS_PULSE_ENABLE; + SPIx.Init.NSSPolarity = SPI_NSS_POLARITY_LOW; + SPIx.Init.FifoThreshold = SPI_FIFO_THRESHOLD_01DATA; + SPIx.Init.MasterSSIdleness = SPI_MASTER_SS_IDLENESS_00CYCLE; + SPIx.Init.MasterInterDataIdleness = SPI_MASTER_INTERDATA_IDLENESS_00CYCLE; + SPIx.Init.MasterReceiverAutoSusp = SPI_MASTER_RX_AUTOSUSP_DISABLE; + SPIx.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_ENABLE; + SPIx.Init.IOSwap = SPI_IO_SWAP_DISABLE; + #endif + pinmap_pinout(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK); pinmap_pinout(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI); - #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN - pinmap_pinout(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO); + #if PIN_EXISTS(TFT_MISO) + // Check these pins in code because they are sometimes defined as analog pin references + if (TFT_MISO_PIN != TFT_MOSI_PIN) pinmap_pinout(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO); #endif - pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TFT_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TFT_SCK_PIN)), GPIO_PULLDOWN); + + //pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TFT_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TFT_SCK_PIN)), GPIO_PULLDOWN); #ifdef SPI1_BASE if (SPIx.Instance == SPI1) { @@ -74,12 +94,17 @@ void TFT_SPI::Init() { #ifdef STM32F1xx __HAL_RCC_DMA1_CLK_ENABLE(); DMAtx.Instance = DMA1_Channel3; + SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4; // SPI1 clock on F1 and F4 is two times faster than SPI2 and SPI3 clock #elif defined(STM32F4xx) __HAL_RCC_DMA2_CLK_ENABLE(); DMAtx.Instance = DMA2_Stream3; DMAtx.Init.Channel = DMA_CHANNEL_3; + SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4; // SPI1 clock on F1 and F4 is two times faster than SPI2 and SPI3 clock + #elif defined(STM32H7xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAtx.Instance = DMA1_Stream4; + DMAtx.Init.Request = DMA_REQUEST_SPI1_TX; #endif - SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4; } #endif #ifdef SPI2_BASE @@ -92,6 +117,10 @@ void TFT_SPI::Init() { __HAL_RCC_DMA1_CLK_ENABLE(); DMAtx.Instance = DMA1_Stream4; DMAtx.Init.Channel = DMA_CHANNEL_0; + #elif defined(STM32H7xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAtx.Instance = DMA1_Stream4; + DMAtx.Init.Request = DMA_REQUEST_SPI2_TX; #endif } #endif @@ -105,165 +134,244 @@ void TFT_SPI::Init() { __HAL_RCC_DMA1_CLK_ENABLE(); DMAtx.Instance = DMA1_Stream5; DMAtx.Init.Channel = DMA_CHANNEL_0; + #elif defined(STM32H7xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAtx.Instance = DMA1_Stream4; + DMAtx.Init.Request = DMA_REQUEST_SPI3_TX; #endif } #endif - HAL_SPI_Init(&SPIx); - DMAtx.Init.Direction = DMA_MEMORY_TO_PERIPH; DMAtx.Init.PeriphInc = DMA_PINC_DISABLE; DMAtx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; DMAtx.Init.Mode = DMA_NORMAL; DMAtx.Init.Priority = DMA_PRIORITY_LOW; - #ifdef STM32F4xx + #if ANY(STM32F4xx, STM32H7xx) DMAtx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; #endif } -void TFT_SPI::DataTransferBegin(uint16_t DataSize) { - SPIx.Init.DataSize = DataSize == DATASIZE_8BIT ? SPI_DATASIZE_8BIT : SPI_DATASIZE_16BIT; +void TFT_SPI::dataTransferBegin(uint16_t dataSize) { + SPIx.Init.DataSize = dataSize; HAL_SPI_Init(&SPIx); WRITE(TFT_CS_PIN, LOW); } -#ifdef TFT_DEFAULT_DRIVER - #include "../../../lcd/tft_io/tft_ids.h" -#endif +#include "../../../lcd/tft_io/tft_ids.h" + +uint32_t TFT_SPI::getID() { + DEBUG_ECHOLNPGM("TFT_SPI::getID()"); + + uint32_t id = readID(LCD_READ_ID); + #if ENABLED(DEBUG_TFT_IO) + char debug_register[3], debug_value[5]; + sprintf_P(debug_register, PSTR("%02X"), LCD_READ_ID); + sprintf_P(debug_value, PSTR("%04X"), uint16_t(id)); + DEBUG_ECHOLNPGM(" readID(0x", debug_register, ") : 0x", debug_value); + #endif -uint32_t TFT_SPI::GetID() { - uint32_t id; - id = ReadID(LCD_READ_ID); if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { - id = ReadID(LCD_READ_ID4); - #ifdef TFT_DEFAULT_DRIVER - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) - id = TFT_DEFAULT_DRIVER; + id = readID(LCD_READ_ID4); + #if ENABLED(DEBUG_TFT_IO) + sprintf_P(debug_register, PSTR("%02X"), LCD_READ_ID4); + sprintf_P(debug_value, PSTR("%04X"), uint16_t(id)); + DEBUG_ECHOLNPGM(" readID(0x", debug_register, ") : 0x", debug_value); #endif - } + } + + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { + id = TFT_DEFAULT_DRIVER; + #if ENABLED(DEBUG_TFT_IO) + sprintf_P(debug_value, PSTR("%04X"), uint16_t(id)); + DEBUG_ECHOLNPGM(" Fallback to TFT_DEFAULT_DRIVER : 0x", debug_value); + #endif + } + #endif + return id; } -uint32_t TFT_SPI::ReadID(uint16_t Reg) { - uint32_t Data = 0; +uint32_t TFT_SPI::readID(const uint16_t inReg) { + uint32_t data = 0; #if PIN_EXISTS(TFT_MISO) uint32_t BaudRatePrescaler = SPIx.Init.BaudRatePrescaler; - uint32_t i; + SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64; - SPIx.Init.BaudRatePrescaler = SPIx.Instance == SPI1 ? SPI_BAUDRATEPRESCALER_8 : SPI_BAUDRATEPRESCALER_4; - DataTransferBegin(DATASIZE_8BIT); - WriteReg(Reg); + dataTransferBegin(DATASIZE_8BIT); + writeReg(inReg); if (SPIx.Init.Direction == SPI_DIRECTION_1LINE) SPI_1LINE_RX(&SPIx); - __HAL_SPI_ENABLE(&SPIx); - for (i = 0; i < 4; i++) { - #if TFT_MISO_PIN != TFT_MOSI_PIN - //if (hspi->Init.Direction == SPI_DIRECTION_2LINES) { - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} + #ifdef STM32H7xx + for (uint32_t i = 0; i < 4; i++) { + MODIFY_REG(SPIx.Instance->CR2, SPI_CR2_TSIZE, 1); + __HAL_SPI_ENABLE(&SPIx); + SET_BIT(SPIx.Instance->CR1, SPI_CR1_CSTART); + + if (SPIx.Init.Direction == SPI_DIRECTION_2LINES) SPIx.Instance->TXDR = 0; + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_EOT)) { /* nada */ } + data = (data << 8) | SPIx.Instance->RXDR; + __HAL_SPI_DISABLE(&SPIx); + __HAL_SPI_CLEAR_EOTFLAG(&SPIx); + __HAL_SPI_CLEAR_TXTFFLAG(&SPIx); + } + #else + __HAL_SPI_ENABLE(&SPIx); + for (uint32_t i = 0; i < 4; i++) { + if (SPIx.Init.Direction == SPI_DIRECTION_2LINES) { + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) { /* nada */ } SPIx.Instance->DR = 0; - //} - #endif - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_RXNE)) {} - Data = (Data << 8) | SPIx.Instance->DR; - } + } + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_RXNE)) { /* nada */ } + data = (data << 8) | SPIx.Instance->DR; + } + #endif - __HAL_SPI_DISABLE(&SPIx); - DataTransferEnd(); - - SPIx.Init.BaudRatePrescaler = BaudRatePrescaler; + dataTransferEnd(); + #if DISABLED(DEBUG_TFT_IO) + SPIx.Init.BaudRatePrescaler = BaudRatePrescaler; + #endif #endif - return Data >> 7; + DEBUG_ECHOLNPGM(" raw data : ", data); + return data >> 7; } bool TFT_SPI::isBusy() { - #if defined(STM32F1xx) - volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET; + #ifdef STM32F1xx + #define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CCR & DMA_CCR_EN) + #define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->Instance->CPAR != 0) #elif defined(STM32F4xx) - volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN; + #define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR & DMA_SxCR_EN) + #define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->Instance->PAR != 0) + #elif defined(STM32H7xx) + #define __IS_DMA_ENABLED(__HANDLE__) (((DMA_Stream_TypeDef *)((__HANDLE__)->Instance))->CR & DMA_SxCR_EN) + #define __IS_DMA_CONFIGURED(__HANDLE__) (((DMA_Stream_TypeDef *)((__HANDLE__)->Instance))->PAR != 0) #endif - if (dmaEnabled) { - if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) - Abort(); + + if (!__IS_DMA_CONFIGURED(&DMAtx)) return false; + + if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx))) { + // You should not be here - DMA transfer error flag is set + // Abort DMA transfer and release SPI } - else - Abort(); - return dmaEnabled; + else { + // Check if DMA transfer completed flag is set + if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) == 0) return true; + #ifdef STM32H7xx + // Check if SPI data transfer is completed + if (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_EOT)) return true; + #else + // Check if SPI transmit butter is empty and SPI is idle + if ((!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) || (__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY))) return true; + #endif + } + + abort(); + return true; } -void TFT_SPI::Abort() { - // Wait for any running spi - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} - while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {} - // First, abort any running dma - HAL_DMA_Abort(&DMAtx); - // DeInit objects +void TFT_SPI::abort() { + HAL_DMA_Abort(&DMAtx); // Abort DMA transfer if any HAL_DMA_DeInit(&DMAtx); - HAL_SPI_DeInit(&SPIx); - // Deselect CS - DataTransferEnd(); + + #ifdef STM32H7xx + CLEAR_BIT(SPIx.Instance->CFG1, SPI_CFG1_TXDMAEN); + __HAL_SPI_CLEAR_EOTFLAG(&SPIx); + __HAL_SPI_CLEAR_TXTFFLAG(&SPIx); + #else + CLEAR_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); + #endif + + dataTransferEnd(); // Stop SPI and deselect CS } -void TFT_SPI::Transmit(uint16_t Data) { - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); +void TFT_SPI::transmit(uint16_t data) { + if (SPIx.Init.Direction == SPI_DIRECTION_1LINE) SPI_1LINE_TX(&SPIx); - __HAL_SPI_ENABLE(&SPIx); + #ifdef STM32H7xx + MODIFY_REG(SPIx.Instance->CR2, SPI_CR2_TSIZE, 1); + __HAL_SPI_ENABLE(&SPIx); + SET_BIT(SPIx.Instance->CR1, SPI_CR1_CSTART); - SPIx.Instance->DR = Data; + SPIx.Instance->TXDR = data; - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} - while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {} + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_SR_EOT)) { /* nada */ } - if (TFT_MISO_PIN != TFT_MOSI_PIN) - __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read + __HAL_SPI_CLEAR_EOTFLAG(&SPIx); + __HAL_SPI_CLEAR_TXTFFLAG(&SPIx); + __HAL_SPI_DISABLE(&SPIx); + #else + __HAL_SPI_ENABLE(&SPIx); + SPIx.Instance->DR = data; + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) { /* nada */ } // Wait for data transfer to actually start + while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) { /* nada */ } // Wait until SPI is idle + #endif + + if (SPIx.Init.Direction == SPI_DIRECTION_2LINES) __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received data is not read } -void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - // Wait last dma finish, to start another - while (isBusy()) { /* nada */ } - - DMAtx.Init.MemInc = MemoryIncrease; +void TFT_SPI::transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + DMAtx.Init.MemInc = memoryIncrease; HAL_DMA_Init(&DMAtx); - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); + if (SPIx.Init.Direction == SPI_DIRECTION_1LINE) SPI_1LINE_TX(&SPIx); - DataTransferBegin(); + dataTransferBegin(); - HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count); - __HAL_SPI_ENABLE(&SPIx); + #ifdef STM32H7xx + HAL_DMA_Start(&DMAtx, (uint32_t)data, (uint32_t)&(SPIx.Instance->TXDR), count); - SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request + CLEAR_BIT(SPIx.Instance->CFG1, SPI_CFG1_TXDMAEN); + MODIFY_REG(SPIx.Instance->CR2, SPI_CR2_TSIZE, count); + SET_BIT(SPIx.Instance->CFG1, SPI_CFG1_TXDMAEN); // Enable Tx DMA Request + __HAL_SPI_ENABLE(&SPIx); + SET_BIT(SPIx.Instance->CR1, SPI_CR1_CSTART); + #else + HAL_DMA_Start(&DMAtx, (uint32_t)data, (uint32_t)&(SPIx.Instance->DR), count); + + __HAL_SPI_ENABLE(&SPIx); + SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request + #endif + + TERN_(TFT_SHARED_IO, while (isBusy())); +} + +void TFT_SPI::transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + transmitDMA(memoryIncrease, data, count); HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); - Abort(); + #ifdef STM32H7xx + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_SR_EOT)) { /* nada */ } + #else + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) { /* nada */ } + while (__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) { /* nada */ } + #endif + abort(); } #if ENABLED(USE_SPI_DMA_TC) + void TFT_SPI::transmitDMA_IT(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { - void TFT_SPI::TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - - DMAtx.Init.MemInc = MemoryIncrease; + DMAtx.Init.MemInc = memoryIncrease; HAL_DMA_Init(&DMAtx); - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); + if (SPIx.Init.Direction == SPI_DIRECTION_1LINE) SPI_1LINE_TX(&SPIx); - DataTransferBegin(); + dataTransferBegin(); HAL_NVIC_SetPriority(DMA2_Stream3_IRQn, 5, 0); HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn); - HAL_DMA_Start_IT(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count); + HAL_DMA_Start_IT(&DMAtx, (uint32_t)data, (uint32_t)&(SPIx.Instance->DR), count); __HAL_SPI_ENABLE(&SPIx); SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request } - extern "C" void DMA2_Stream3_IRQHandler(void) { HAL_DMA_IRQHandler(&TFT_SPI::DMAtx); } - + extern "C" void DMA2_Stream3_IRQHandler(void) { TFT_SPI::DMA_IRQHandler(); } #endif #endif // HAS_SPI_TFT diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.h b/Marlin/src/HAL/STM32/tft/tft_spi.h index de051e2294..6345c91f6c 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32/tft/tft_spi.h @@ -25,8 +25,10 @@ #include "stm32f1xx_hal.h" #elif defined(STM32F4xx) #include "stm32f4xx_hal.h" +#elif defined(STM32H7xx) + #include "stm32h7xx_hal.h" #else - #error SPI TFT is currently only supported on STM32F1 and STM32F4 hardware. + #error SPI TFT is currently only supported on STM32F1, STM32F4 and STM32H7 hardware. #endif #ifndef LCD_READ_ID @@ -38,47 +40,49 @@ #define DATASIZE_8BIT SPI_DATASIZE_8BIT #define DATASIZE_16BIT SPI_DATASIZE_16BIT +#define DATASIZE_32BIT SPI_DATASIZE_32BIT #define TFT_IO_DRIVER TFT_SPI +#define DMA_MAX_WORDS 0xFFFF class TFT_SPI { private: static SPI_HandleTypeDef SPIx; + static DMA_HandleTypeDef DMAtx; - - static uint32_t ReadID(uint16_t Reg); - static void Transmit(uint16_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static uint32_t readID(const uint16_t inReg); + static void transmit(uint16_t data); + static void transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count); + static void transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count); #if ENABLED(USE_SPI_DMA_TC) - static void TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static void transmitDMA_IT(uint32_t memoryIncrease, uint16_t *data, uint16_t count); #endif public: - static DMA_HandleTypeDef DMAtx; - - static void Init(); - static uint32_t GetID(); + static void init(); + static uint32_t getID(); static bool isBusy(); - static void Abort(); + static void abort(); - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT); - static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); }; - static void DataTransferAbort(); + static void dataTransferBegin(uint16_t dataWidth=DATASIZE_16BIT); + static void dataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); __HAL_SPI_DISABLE(&SPIx); }; + static void dataTransferAbort(); - static void WriteData(uint16_t Data) { Transmit(Data); } - static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); } + static void writeData(uint16_t data) { transmit(data); } + static void writeReg(const uint16_t inReg) { WRITE(TFT_A0_PIN, LOW); transmit(inReg); WRITE(TFT_A0_PIN, HIGH); } - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } + static void writeSequence_DMA(uint16_t *data, uint16_t count) { transmitDMA(DMA_MINC_ENABLE, data, count); } + static void writeMultiple_DMA(uint16_t color, uint16_t count) { static uint16_t data; data = color; transmitDMA(DMA_MINC_DISABLE, &data, count); } #if ENABLED(USE_SPI_DMA_TC) - static void WriteSequenceIT(uint16_t *Data, uint16_t Count) { TransmitDMA_IT(DMA_MINC_ENABLE, Data, Count); } + static void writeSequenceIT(uint16_t *data, uint16_t count) { transmitDMA_IT(DMA_MINC_ENABLE, data, count); } + inline static void DMA_IRQHandler() { HAL_DMA_IRQHandler(&TFT_SPI::DMAtx); } #endif - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } - static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; - while (Count > 0) { - TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); - Count = Count > 0xFFFF ? Count - 0xFFFF : 0; + static void writeSequence(uint16_t *data, uint16_t count) { transmit(DMA_MINC_ENABLE, data, count); } + static void writeMultiple(uint16_t color, uint32_t count) { + while (count > 0) { + transmit(DMA_MINC_DISABLE, &color, count > DMA_MAX_WORDS ? DMA_MAX_WORDS : count); + count = count > DMA_MAX_WORDS ? count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index cf4a8f18e9..c5645ad79c 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -35,7 +35,7 @@ uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } SPI_HandleTypeDef XPT2046::SPIx; -void XPT2046::Init() { +void XPT2046::init() { SPI_TypeDef *spiInstance; OUT_WRITE(TOUCH_CS_PIN, HIGH); @@ -56,7 +56,6 @@ void XPT2046::Init() { SPIx.Init.NSS = SPI_NSS_SOFT; SPIx.Init.Mode = SPI_MODE_MASTER; SPIx.Init.Direction = SPI_DIRECTION_2LINES; - SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8; SPIx.Init.CLKPhase = SPI_PHASE_2EDGE; SPIx.Init.CLKPolarity = SPI_POLARITY_HIGH; SPIx.Init.DataSize = SPI_DATASIZE_8BIT; @@ -65,6 +64,20 @@ void XPT2046::Init() { SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; SPIx.Init.CRCPolynomial = 10; + #ifndef STM32H7xx + SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8; // 4.5 MBit/s for F103 and 5.25 MBit/s for F407 + #else + SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16; // 5 MBit/s for H743 + SPIx.Init.NSSPMode = SPI_NSS_PULSE_ENABLE; + SPIx.Init.NSSPolarity = SPI_NSS_POLARITY_LOW; + SPIx.Init.FifoThreshold = SPI_FIFO_THRESHOLD_01DATA; + SPIx.Init.MasterSSIdleness = SPI_MASTER_SS_IDLENESS_00CYCLE; + SPIx.Init.MasterInterDataIdleness = SPI_MASTER_INTERDATA_IDLENESS_00CYCLE; + SPIx.Init.MasterReceiverAutoSusp = SPI_MASTER_RX_AUTOSUSP_DISABLE; + SPIx.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_ENABLE; + SPIx.Init.IOSwap = SPI_IO_SWAP_DISABLE; + #endif + pinmap_pinout(digitalPinToPinName(TOUCH_SCK_PIN), PinMap_SPI_SCLK); pinmap_pinout(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI); pinmap_pinout(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO); @@ -106,9 +119,8 @@ bool XPT2046::isTouched() { ); } -bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { - if (isBusy()) return false; - if (!isTouched()) return false; +bool XPT2046::getRawPoint(int16_t * const x, int16_t * const y) { + if (isBusy() || !isTouched()) return false; *x = getRawData(XPT2046_X); *y = getRawData(XPT2046_Y); return isTouched(); @@ -117,14 +129,14 @@ bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { uint16_t data[3]; - DataTransferBegin(); + dataTransferBegin(); for (uint16_t i = 0; i < 3 ; i++) { IO(coordinate); data[i] = (IO() << 4) | (IO() >> 4); } - DataTransferEnd(); + dataTransferEnd(); uint16_t delta01 = delta(data[0], data[1]); uint16_t delta02 = delta(data[0], data[2]); @@ -140,17 +152,34 @@ uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { return (data[0] + data[1]) >> 1; } -uint16_t XPT2046::HardwareIO(uint16_t data) { - __HAL_SPI_ENABLE(&SPIx); - while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} - SPIx.Instance->DR = data; - while ((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {} - __HAL_SPI_DISABLE(&SPIx); +uint16_t XPT2046::hardwareIO(uint16_t data) { + #ifdef STM32H7xx + MODIFY_REG(SPIx.Instance->CR2, SPI_CR2_TSIZE, 1); + __HAL_SPI_ENABLE(&SPIx); + SET_BIT(SPIx.Instance->CR1, SPI_CR1_CSTART); - return SPIx.Instance->DR; + SPIx.Instance->TXDR = data; + + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_SR_EOT)) {} + data = SPIx.Instance->RXDR; + + __HAL_SPI_DISABLE(&SPIx); + __HAL_SPI_CLEAR_EOTFLAG(&SPIx); + __HAL_SPI_CLEAR_TXTFFLAG(&SPIx); + + return data; + #else + __HAL_SPI_ENABLE(&SPIx); + while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} + SPIx.Instance->DR = data; + while ((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {} + __HAL_SPI_DISABLE(&SPIx); + + return SPIx.Instance->DR; + #endif } -uint16_t XPT2046::SoftwareIO(uint16_t data) { +uint16_t XPT2046::softwareIO(uint16_t data) { uint16_t result = 0; for (uint8_t j = 0x80; j > 0; j >>= 1) { diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h index 71de6b0025..f3d3e53291 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32/tft/xpt2046.h @@ -22,9 +22,13 @@ #pragma once #ifdef STM32F1xx - #include + #include "stm32f1xx_hal.h" #elif defined(STM32F4xx) - #include + #include "stm32f4xx_hal.h" +#elif defined(STM32H7xx) + #include "stm32h7xx_hal.h" +#else + #error SPI Touch Screen is currently only supported on STM32F1, STM32F4 and STM32H7 hardware. #endif #include "../../../inc/MarlinConfig.h" @@ -45,7 +49,11 @@ #define TOUCH_INT_PIN -1 #endif -#define XPT2046_DFR_MODE 0x00 +#if PIN_EXISTS(TOUCH_INT) + #define XPT2046_DFR_MODE 0x00 +#else + #define XPT2046_DFR_MODE 0x01 +#endif #define XPT2046_SER_MODE 0x04 #define XPT2046_CONTROL 0x80 @@ -69,13 +77,13 @@ private: static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static void DataTransferBegin() { if (SPIx.Instance) { HAL_SPI_Init(&SPIx); } WRITE(TOUCH_CS_PIN, LOW); }; - static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; - static uint16_t HardwareIO(uint16_t data); - static uint16_t SoftwareIO(uint16_t data); - static uint16_t IO(uint16_t data = 0) { return SPIx.Instance ? HardwareIO(data) : SoftwareIO(data); } + static void dataTransferBegin() { if (SPIx.Instance) { HAL_SPI_Init(&SPIx); } WRITE(TOUCH_CS_PIN, LOW); }; + static void dataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; + static uint16_t hardwareIO(uint16_t data); + static uint16_t softwareIO(uint16_t data); + static uint16_t IO(uint16_t data = 0) { return SPIx.Instance ? hardwareIO(data) : softwareIO(data); } public: - static void Init(); - static bool getRawPoint(int16_t *x, int16_t *y); + static void init(); + static bool getRawPoint(int16_t * const x, int16_t * const y); }; diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index e68b59c46f..5b58a915f0 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -81,10 +81,6 @@ #define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used. #endif -#ifndef HAL_TIMER_RATE - #define HAL_TIMER_RATE GetStepperTimerClkFreq() -#endif - #ifndef STEP_TIMER #define STEP_TIMER MCU_STEP_TIMER #endif @@ -141,7 +137,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { */ timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally - timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT); + timer_instance[timer_num]->setOverflow(_MIN(HAL_TIMER_TYPE_MAX, hal_timer_t((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* / frequency */)), TICK_FORMAT); break; case MF_TIMER_TEMP: // TEMP TIMER - any available 16bit timer timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV); @@ -292,9 +288,9 @@ static constexpr int get_timer_num_from_base_address(uintptr_t base_address) { // constexpr doesn't like using the base address pointers that timers evaluate to. // We can get away with casting them to uintptr_t, if we do so inside an array. // GCC will not currently do it directly to a uintptr_t. -IF_ENABLED(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)}); -IF_ENABLED(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)}); -IF_ENABLED(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)}); +TERN_(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)}); +TERN_(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)}); +TERN_(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)}); enum TimerPurpose { TP_SERIAL, TP_TONE, TP_SERVO, TP_STEP, TP_TEMP }; @@ -316,8 +312,8 @@ static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = { }; static constexpr bool verify_no_timer_conflicts() { - LOOP_L_N(i, COUNT(timers_in_use)) - LOOP_S_L_N(j, i + 1, COUNT(timers_in_use)) + for (uint8_t i = 0; i < COUNT(timers_in_use); ++i) + for (uint8_t j = i + 1; j < COUNT(timers_in_use); ++j) if (timers_in_use[i].t == timers_in_use[j].t) return false; return true; } diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 6828998198..a6c9204a77 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -38,7 +38,7 @@ // of adding a run-time check and HAL_TIMER_TYPE_MAX is refactored to allow unique // values for each timer. #define hal_timer_t uint32_t -#define HAL_TIMER_TYPE_MAX UINT16_MAX +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) // Marlin timer_instance[] content (unrelated to timer selection) #define MF_TIMER_STEP 0 // Timer Index for Stepper @@ -48,23 +48,28 @@ #define TIMER_INDEX_(T) TIMER##T##_INDEX // TIMER#_INDEX enums (timer_index_t) depend on TIM#_BASE defines. #define TIMER_INDEX(T) TIMER_INDEX_(T) // Convert Timer ID to HardwareTimer_Handle index. -#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz +#ifndef HAL_TIMER_RATE + extern uint32_t GetStepperTimerClkFreq(); + #define HAL_TIMER_RATE GetStepperTimerClkFreq() +#endif -// TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp -#define STEPPER_TIMER_RATE 2000000 // 2 Mhz -extern uint32_t GetStepperTimerClkFreq(); -#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / (STEPPER_TIMER_RATE)) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +// Timer configuration constants +#define STEPPER_TIMER_RATE 2000000 +#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() should run at ~1kHz -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +// Timer prescaler calculations +#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE)) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (ticks/μs) Stepper Timer ticks per µs -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +// Pulse Timer (counter) calculations +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) + +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) extern void Step_Handler(); @@ -116,5 +121,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha } } -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/STM32/u8g/LCD_defines.h b/Marlin/src/HAL/STM32/u8g/LCD_defines.h new file mode 100644 index 0000000000..96f73002a5 --- /dev/null +++ b/Marlin/src/HAL/STM32/u8g/LCD_defines.h @@ -0,0 +1,35 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * STM32 LCD-specific defines + */ + +uint8_t u8g_com_HAL_STM32_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // u8g_com_stm32duino_swspi.cpp +#define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_STM32_sw_spi_fn + +uint8_t u8g_com_stm32duino_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // See U8glib-HAL +#define U8G_COM_HAL_HW_SPI_FN u8g_com_stm32duino_hw_spi_fn + +uint8_t u8g_com_stm32duino_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // u8g_com_stm32duino_ssd_i2c.cpp +#define U8G_COM_SSD_I2C_HAL u8g_com_stm32duino_ssd_i2c_fn diff --git a/Marlin/src/HAL/STM32/u8g/u8g_com_stm32duino_ssd_i2c.cpp b/Marlin/src/HAL/STM32/u8g/u8g_com_stm32duino_ssd_i2c.cpp new file mode 100644 index 0000000000..72abe1a656 --- /dev/null +++ b/Marlin/src/HAL/STM32/u8g/u8g_com_stm32duino_ssd_i2c.cpp @@ -0,0 +1,194 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * 2-Wire I2C COM Driver + * + * Handles both Hardware and Software I2C so any pins can be used as SDA and SLC. + * Wire library is used for Hardware I2C. + * SlowSoftWire is used for Software I2C. + * + * Wire / SoftWire library selection can be done automatically at runtime. + * + * SDA and SLC pins must be named DOGLCD_SDA_PIN, DOGLCD_SCL_PIN to distinguish + * from other I2C devices (e.g., EEPROM) that use I2C_SDA_PIN, I2C_SLC_PIN. + */ +#ifdef ARDUINO_ARCH_STM32 + +#include "../../../inc/MarlinConfig.h" + +#if HAS_U8GLIB_I2C_OLED + +#include + +#if ENABLED(U8G_USES_HW_I2C) + #include + #ifndef MASTER_ADDRESS + #define MASTER_ADDRESS 0x01 + #endif +#endif + +#if ENABLED(U8G_USES_SW_I2C) + #include + #include +#endif + +/** + * BUFFER_LENGTH is defined in libraries\Wire\utility\WireBase.h + * Default value is 32 + * Increase this value to 144 to send U8G_COM_MSG_WRITE_SEQ in single block + */ +#ifndef BUFFER_LENGTH + #define BUFFER_LENGTH 32 +#endif +#if BUFFER_LENGTH > 144 + #error "BUFFER_LENGTH should not be greater than 144." +#endif +#define I2C_MAX_LENGTH (BUFFER_LENGTH - 1) + +uint8_t u8g_com_stm32duino_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + // Hardware I2C flag + #ifdef COMPILE_TIME_I2C_IS_HARDWARE + constexpr bool isHardI2C = ENABLED(COMPILE_TIME_I2C_IS_HARDWARE); + #else + static bool isHardI2C = false; + static bool i2c_initialized = false; // Flag to only run init/linking code once + if (!i2c_initialized) { // Init runtime linkages + i2c_initialized = true; // Only do this once + I2C_TypeDef *i2cInstance1 = (I2C_TypeDef *)pinmap_peripheral(digitalPinToPinName(DOGLCD_SDA_PIN), PinMap_I2C_SDA); + I2C_TypeDef *i2cInstance2 = (I2C_TypeDef *)pinmap_peripheral(digitalPinToPinName(DOGLCD_SCL_PIN), PinMap_I2C_SCL); + isHardI2C = (i2cInstance1 && (i2cInstance1 == i2cInstance2)); // Found hardware I2C controller + } + #endif + + static uint8_t msgInitCount = 0; // Ignore all messages until 2nd U8G_COM_MSG_INIT + if (msgInitCount) { + if (msg == U8G_COM_MSG_INIT) msgInitCount--; + if (msgInitCount) return -1; + } + + static uint8_t control; + if (isHardI2C) { // Found hardware I2C controller + #if ENABLED(U8G_USES_HW_I2C) + static TwoWire wire2; // A TwoWire object for use below + switch (msg) { + case U8G_COM_MSG_INIT: + wire2.setClock(400000); + wire2.setSCL(DOGLCD_SCL_PIN); + wire2.setSDA(DOGLCD_SDA_PIN); + wire2.begin(MASTER_ADDRESS, 0); // Start as master + break; + + case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1) + control = arg_val ? 0x40 : 0x00; + break; + + case U8G_COM_MSG_WRITE_BYTE: + wire2.beginTransmission(0x3C); + wire2.write(control); + wire2.write(arg_val); + wire2.endTransmission(); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t* dataptr = (uint8_t*)arg_ptr; + #ifdef I2C_MAX_LENGTH + while (arg_val > 0) { + wire2.beginTransmission(0x3C); + wire2.write(control); + if (arg_val <= I2C_MAX_LENGTH) { + wire2.write(dataptr, arg_val); + arg_val = 0; + } + else { + wire2.write(dataptr, I2C_MAX_LENGTH); + arg_val -= I2C_MAX_LENGTH; + dataptr += I2C_MAX_LENGTH; + } + wire2.endTransmission(); + } + #else + wire2.beginTransmission(0x3C); + wire2.write(control); + wire2.write(dataptr, arg_val); + wire2.endTransmission(); + #endif // I2C_MAX_LENGTH + break; + } + } + #endif // U8G_USES_HW_I2C + } + else { // Software I2C + #if ENABLED(U8G_USES_SW_I2C) + static SlowSoftWire sWire = SlowSoftWire(DOGLCD_SDA_PIN, DOGLCD_SCL_PIN); + + switch (msg) { + case U8G_COM_MSG_INIT: + sWire.setClock(400000); + sWire.begin(); // Start as master + break; + + case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1) + control = arg_val ? 0x40 : 0x00; + break; + + case U8G_COM_MSG_WRITE_BYTE: + sWire.beginTransmission((uint8_t)0x3C); + sWire.write((uint8_t)control); + sWire.write((uint8_t)arg_val); + sWire.endTransmission(); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t* dataptr = (uint8_t*)arg_ptr; + #ifdef I2C_MAX_LENGTH + while (arg_val > 0) { + sWire.beginTransmission((uint8_t)0x3C); + sWire.write((uint8_t)control); + if (arg_val <= I2C_MAX_LENGTH) { + sWire.write((const uint8_t *)dataptr, (size_t)arg_val); + arg_val = 0; + } + else { + sWire.write((const uint8_t *)dataptr, I2C_MAX_LENGTH); + arg_val -= I2C_MAX_LENGTH; + dataptr += I2C_MAX_LENGTH; + } + sWire.endTransmission(); + } + #else + sWire.beginTransmission((uint8_t)0x3C); + sWire.write((uint8_t)control); + sWire.write((const uint8_t *)dataptr, (size_t)arg_val); + sWire.endTransmission(); + #endif // I2C_MAX_LENGTH + break; + } + } + #endif // U8G_USES_SW_I2C + } + + return 1; +} + +#endif // HAS_U8GLIB_I2C_OLED +#endif // ARDUINO_ARCH_STM32 diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp index 0b2372f3a7..1ca8b19976 100644 --- a/Marlin/src/HAL/STM32/usb_serial.cpp +++ b/Marlin/src/HAL/STM32/usb_serial.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if ENABLED(EMERGENCY_PARSER) && (USBD_USE_CDC || USBD_USE_CDC_MSC) +#if ENABLED(EMERGENCY_PARSER) && ANY(USBD_USE_CDC, USBD_USE_CDC_MSC) #include "usb_serial.h" #include "../../feature/e_parser.h" @@ -56,5 +56,5 @@ void USB_Hook_init() { USBD_CDC_fops.Receive = USBD_CDC_Receive_hook; } -#endif // EMERGENCY_PARSER && USBD_USE_CDC +#endif // EMERGENCY_PARSER && (USBD_USE_CDC || USBD_USE_CDC_MSC) #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index 4d3140001e..fc1680cbf4 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -30,53 +29,8 @@ #include "../../inc/MarlinConfig.h" #include "HAL.h" -#include - -// ------------------------ -// Types -// ------------------------ - -#define __I -#define __IO volatile - typedef struct { - __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5]; - __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - } SCB_Type; - -// ------------------------ -// Local defines -// ------------------------ - -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ +#include "adc.h" +uint16_t adc_results[ADC_COUNT]; // ------------------------ // Serial ports @@ -111,7 +65,8 @@ emergency_parser.update(MSerial0.emergency_state, buf[i + total - len]); } #endif -#endif + +#endif // SERIAL_USB && !HAS_SD_HOST_DRIVE // ------------------------ // Watchdog Timer @@ -172,11 +127,86 @@ void analogWrite(const pin_t pin, int pwm_val8) { uint16_t MarlinHAL::adc_result; +#ifndef VOXELAB_N32 + +#include + +// Init the ADC in continuous capture mode +void MarlinHAL::adc_init() { + static const uint8_t adc_pins[] = { + OPTITEM(HAS_TEMP_ADC_0, TEMP_0_PIN ) + OPTITEM(HAS_TEMP_ADC_1, TEMP_1_PIN ) + OPTITEM(HAS_TEMP_ADC_2, TEMP_2_PIN ) + OPTITEM(HAS_TEMP_ADC_3, TEMP_3_PIN ) + OPTITEM(HAS_TEMP_ADC_4, TEMP_4_PIN ) + OPTITEM(HAS_TEMP_ADC_5, TEMP_5_PIN ) + OPTITEM(HAS_TEMP_ADC_6, TEMP_6_PIN ) + OPTITEM(HAS_TEMP_ADC_7, TEMP_7_PIN ) + OPTITEM(HAS_TEMP_ADC_BED, TEMP_BED_PIN ) + OPTITEM(HAS_TEMP_ADC_CHAMBER, TEMP_CHAMBER_PIN ) + OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE_PIN ) + OPTITEM(HAS_TEMP_ADC_COOLER, TEMP_COOLER_PIN ) + OPTITEM(HAS_TEMP_ADC_BOARD, TEMP_BOARD_PIN ) + OPTITEM(HAS_TEMP_ADC_SOC, TEMP_SOC_PIN ) + OPTITEM(HAS_FILWIDTH_ADC, FILWIDTH_PIN ) + OPTITEM(HAS_FILWIDTH2_ADC, FILWIDTH2_PIN ) + OPTITEM(HAS_ADC_BUTTONS, ADC_KEYPAD_PIN ) + OPTITEM(HAS_JOY_ADC_X, JOY_X_PIN ) + OPTITEM(HAS_JOY_ADC_Y, JOY_Y_PIN ) + OPTITEM(HAS_JOY_ADC_Z, JOY_Z_PIN ) + OPTITEM(POWER_MONITOR_CURRENT, POWER_MONITOR_CURRENT_PIN) + OPTITEM(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN) + }; + static STM32ADC adc(ADC1); + // Configure the ADC + adc.calibrate(); + adc.setSampleRate((F_CPU > 72000000) ? ADC_SMPR_71_5 : ADC_SMPR_41_5); // 71.5 or 41.5 ADC cycles + adc.setPins((uint8_t *)adc_pins, ADC_COUNT); + adc.setDMA(adc_results, uint16_t(ADC_COUNT), uint32_t(DMA_MINC_MODE | DMA_CIRC_MODE), nullptr); + adc.setScanMode(); + adc.setContinuous(); + adc.startConversion(); +} + +#endif // !VOXELAB_N32 + +void MarlinHAL::adc_start(const pin_t pin) { + #define __TCASE(N,I) case N: pin_index = I; break; + #define _TCASE(C,N,I) TERN_(C, __TCASE(N, I)) + ADCIndex pin_index; + switch (pin) { + default: return; + _TCASE(HAS_TEMP_ADC_0, TEMP_0_PIN, TEMP_0 ) + _TCASE(HAS_TEMP_ADC_1, TEMP_1_PIN, TEMP_1 ) + _TCASE(HAS_TEMP_ADC_2, TEMP_2_PIN, TEMP_2 ) + _TCASE(HAS_TEMP_ADC_3, TEMP_3_PIN, TEMP_3 ) + _TCASE(HAS_TEMP_ADC_4, TEMP_4_PIN, TEMP_4 ) + _TCASE(HAS_TEMP_ADC_5, TEMP_5_PIN, TEMP_5 ) + _TCASE(HAS_TEMP_ADC_6, TEMP_6_PIN, TEMP_6 ) + _TCASE(HAS_TEMP_ADC_7, TEMP_7_PIN, TEMP_7 ) + _TCASE(HAS_TEMP_ADC_BED, TEMP_BED_PIN, TEMP_BED ) + _TCASE(HAS_TEMP_ADC_CHAMBER, TEMP_CHAMBER_PIN, TEMP_CHAMBER ) + _TCASE(HAS_TEMP_ADC_PROBE, TEMP_PROBE_PIN, TEMP_PROBE ) + _TCASE(HAS_TEMP_ADC_COOLER, TEMP_COOLER_PIN, TEMP_COOLER ) + _TCASE(HAS_TEMP_ADC_BOARD, TEMP_BOARD_PIN, TEMP_BOARD ) + _TCASE(HAS_TEMP_ADC_SOC, TEMP_SOC_PIN, TEMP_SOC ) + _TCASE(HAS_FILWIDTH_ADC, FILWIDTH_PIN, FILWIDTH ) + _TCASE(HAS_FILWIDTH2_ADC, FILWIDTH2_PIN, FILWIDTH2 ) + _TCASE(HAS_ADC_BUTTONS, ADC_KEYPAD_PIN, ADC_KEY ) + _TCASE(HAS_JOY_ADC_X, JOY_X_PIN, JOY_X ) + _TCASE(HAS_JOY_ADC_Y, JOY_Y_PIN, JOY_Y ) + _TCASE(HAS_JOY_ADC_Z, JOY_Z_PIN, JOY_Z ) + _TCASE(POWER_MONITOR_CURRENT, POWER_MONITOR_CURRENT_PIN, POWERMON_CURRENT) + _TCASE(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN, POWERMON_VOLTAGE) + } + adc_result = (adc_results[(int)pin_index] & 0xFFF) >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits +} + // ------------------------ -// Private functions +// Public functions // ------------------------ -static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { +void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used @@ -188,10 +218,6 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { SCB->AIRCR = reg_value; } -// ------------------------ -// Public functions -// ------------------------ - void flashFirmware(const int16_t) { hal.reboot(); } // @@ -224,12 +250,12 @@ void MarlinHAL::init() { #endif #if HAS_SD_HOST_DRIVE MSC_SD_init(); - #elif BOTH(SERIAL_USB, EMERGENCY_PARSER) + #elif ALL(SERIAL_USB, EMERGENCY_PARSER) usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, my_rx_callback); #endif #if PIN_EXISTS(USB_CONNECT) OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection - delay(1000); // Give OS time to notice + delay_ms(1000); // Give OS time to notice WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); #endif TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the minimal serial handler @@ -238,150 +264,20 @@ void MarlinHAL::init() { // HAL idle task void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA - // If Marlin is using the SD card we need to lock it to prevent access from - // a PC via USB. - // Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but - // this will not reliably detect delete operations. To be safe we will lock - // the disk if Marlin has it mounted. Unfortunately there is currently no way - // to unmount the disk from the LCD menu. - // if (IS_SD_PRINTING() || IS_SD_FILE_OPEN()) - /* copy from lpc1768 framework, should be fixed later for process HAS_SD_HOST_DRIVE*/ - // process USB mass storage device class loop - MarlinMSC.loop(); + /** + * When Marlin is using the SD card it should be locked to prevent it being + * accessed from a PC over USB. + * Other HALs use (card.isStillPrinting() || card.isFileOpen()) to check for access + * but this won't reliably detect other file operations. To be safe we just lock + * the drive whenever Marlin has it mounted. LCDs should include an Unmount + * command so drives can be released as needed. + */ + /* Copied from LPC1768 framework. Should be fixed later to process HAS_SD_HOST_DRIVE */ + //if (!drive_locked()) // TODO + MarlinMSC.loop(); // Process USB mass storage device class loop #endif } void MarlinHAL::reboot() { nvic_sys_reset(); } -// ------------------------ -// Free Memory Accessor -// ------------------------ - -extern "C" { - extern unsigned int _ebss; // end of bss section -} - -/** - * TODO: Change this to correct it for libmaple - */ - -// return free memory between end of heap (or end bss) and whatever is current - -/* -#include -//extern caddr_t _sbrk(int incr); -#ifndef CONFIG_HEAP_END -extern char _lm_heap_end; -#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end) -#endif - -extern "C" { - static int freeMemory() { - char top = 't'; - return &top - reinterpret_cast(sbrk(0)); - } - int freeMemory() { - int free_memory; - int heap_end = (int)_sbrk(0); - free_memory = ((int)&free_memory) - ((int)heap_end); - return free_memory; - } -} -*/ - -// ------------------------ -// ADC -// ------------------------ - -enum ADCIndex : uint8_t { - OPTITEM(HAS_TEMP_ADC_0, TEMP_0) - OPTITEM(HAS_TEMP_ADC_1, TEMP_1) - OPTITEM(HAS_TEMP_ADC_2, TEMP_2) - OPTITEM(HAS_TEMP_ADC_3, TEMP_3) - OPTITEM(HAS_TEMP_ADC_4, TEMP_4) - OPTITEM(HAS_TEMP_ADC_5, TEMP_5) - OPTITEM(HAS_TEMP_ADC_6, TEMP_6) - OPTITEM(HAS_TEMP_ADC_7, TEMP_7) - OPTITEM(HAS_HEATED_BED, TEMP_BED) - OPTITEM(HAS_TEMP_CHAMBER, TEMP_CHAMBER) - OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE) - OPTITEM(HAS_TEMP_COOLER, TEMP_COOLER) - OPTITEM(HAS_TEMP_BOARD, TEMP_BOARD) - OPTITEM(FILAMENT_WIDTH_SENSOR, FILWIDTH) - OPTITEM(HAS_ADC_BUTTONS, ADC_KEY) - OPTITEM(HAS_JOY_ADC_X, JOY_X) - OPTITEM(HAS_JOY_ADC_Y, JOY_Y) - OPTITEM(HAS_JOY_ADC_Z, JOY_Z) - OPTITEM(POWER_MONITOR_CURRENT, POWERMON_CURRENT) - OPTITEM(POWER_MONITOR_VOLTAGE, POWERMON_VOLTS) - ADC_COUNT -}; - -static uint16_t adc_results[ADC_COUNT]; - -// Init the AD in continuous capture mode -void MarlinHAL::adc_init() { - static const uint8_t adc_pins[] = { - OPTITEM(HAS_TEMP_ADC_0, TEMP_0_PIN) - OPTITEM(HAS_TEMP_ADC_1, TEMP_1_PIN) - OPTITEM(HAS_TEMP_ADC_2, TEMP_2_PIN) - OPTITEM(HAS_TEMP_ADC_3, TEMP_3_PIN) - OPTITEM(HAS_TEMP_ADC_4, TEMP_4_PIN) - OPTITEM(HAS_TEMP_ADC_5, TEMP_5_PIN) - OPTITEM(HAS_TEMP_ADC_6, TEMP_6_PIN) - OPTITEM(HAS_TEMP_ADC_7, TEMP_7_PIN) - OPTITEM(HAS_HEATED_BED, TEMP_BED_PIN) - OPTITEM(HAS_TEMP_CHAMBER, TEMP_CHAMBER_PIN) - OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE_PIN) - OPTITEM(HAS_TEMP_COOLER, TEMP_COOLER_PIN) - OPTITEM(HAS_TEMP_BOARD, TEMP_BOARD_PIN) - OPTITEM(FILAMENT_WIDTH_SENSOR, FILWIDTH_PIN) - OPTITEM(HAS_ADC_BUTTONS, ADC_KEYPAD_PIN) - OPTITEM(HAS_JOY_ADC_X, JOY_X_PIN) - OPTITEM(HAS_JOY_ADC_Y, JOY_Y_PIN) - OPTITEM(HAS_JOY_ADC_Z, JOY_Z_PIN) - OPTITEM(POWER_MONITOR_CURRENT, POWER_MONITOR_CURRENT_PIN) - OPTITEM(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN) - }; - static STM32ADC adc(ADC1); - // configure the ADC - adc.calibrate(); - adc.setSampleRate((F_CPU > 72000000) ? ADC_SMPR_71_5 : ADC_SMPR_41_5); // 71.5 or 41.5 ADC cycles - adc.setPins((uint8_t *)adc_pins, ADC_COUNT); - adc.setDMA(adc_results, uint16_t(ADC_COUNT), uint32_t(DMA_MINC_MODE | DMA_CIRC_MODE), nullptr); - adc.setScanMode(); - adc.setContinuous(); - adc.startConversion(); -} - -void MarlinHAL::adc_start(const pin_t pin) { - #define __TCASE(N,I) case N: pin_index = I; break; - #define _TCASE(C,N,I) TERN_(C, __TCASE(N, I)) - ADCIndex pin_index; - switch (pin) { - default: return; - _TCASE(HAS_TEMP_ADC_0, TEMP_0_PIN, TEMP_0) - _TCASE(HAS_TEMP_ADC_1, TEMP_1_PIN, TEMP_1) - _TCASE(HAS_TEMP_ADC_2, TEMP_2_PIN, TEMP_2) - _TCASE(HAS_TEMP_ADC_3, TEMP_3_PIN, TEMP_3) - _TCASE(HAS_TEMP_ADC_4, TEMP_4_PIN, TEMP_4) - _TCASE(HAS_TEMP_ADC_5, TEMP_5_PIN, TEMP_5) - _TCASE(HAS_TEMP_ADC_6, TEMP_6_PIN, TEMP_6) - _TCASE(HAS_TEMP_ADC_7, TEMP_7_PIN, TEMP_7) - _TCASE(HAS_HEATED_BED, TEMP_BED_PIN, TEMP_BED) - _TCASE(HAS_TEMP_CHAMBER, TEMP_CHAMBER_PIN, TEMP_CHAMBER) - _TCASE(HAS_TEMP_ADC_PROBE, TEMP_PROBE_PIN, TEMP_PROBE) - _TCASE(HAS_TEMP_COOLER, TEMP_COOLER_PIN, TEMP_COOLER) - _TCASE(HAS_TEMP_BOARD, TEMP_BOARD_PIN, TEMP_BOARD) - _TCASE(HAS_JOY_ADC_X, JOY_X_PIN, JOY_X) - _TCASE(HAS_JOY_ADC_Y, JOY_Y_PIN, JOY_Y) - _TCASE(HAS_JOY_ADC_Z, JOY_Z_PIN, JOY_Z) - _TCASE(FILAMENT_WIDTH_SENSOR, FILWIDTH_PIN, FILWIDTH) - _TCASE(HAS_ADC_BUTTONS, ADC_KEYPAD_PIN, ADC_KEY) - _TCASE(POWER_MONITOR_CURRENT, POWER_MONITOR_CURRENT_PIN, POWERMON_CURRENT) - _TCASE(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN, POWERMON_VOLTS) - } - adc_result = (adc_results[(int)pin_index] & 0xFFF) >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits -} - #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index b14b5f7e79..2c7321403f 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -41,11 +40,9 @@ #include "../../inc/MarlinConfigPre.h" #if HAS_SD_HOST_DRIVE - #include "msc_sd.h" + #include "sd/msc_sd.h" #endif -#include "MarlinSerial.h" - // ------------------------ // Defines // ------------------------ @@ -65,90 +62,17 @@ #endif #endif -// ------------------------ -// Serial ports -// ------------------------ +// +// Serial Ports +// -#ifdef SERIAL_USB - typedef ForwardSerial1Class< USBSerial > DefaultSerial1; - extern DefaultSerial1 MSerial0; - #if HAS_SD_HOST_DRIVE - #define UsbSerial MarlinCompositeSerial - #else - #define UsbSerial MSerial0 - #endif -#endif - -#define _MSERIAL(X) MSerial##X -#define MSERIAL(X) _MSERIAL(X) - -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) - #define NUM_UARTS 5 -#else - #define NUM_UARTS 3 -#endif - -#if SERIAL_PORT == -1 - #define MYSERIAL1 UsbSerial -#elif WITHIN(SERIAL_PORT, 1, NUM_UARTS) - #define MYSERIAL1 MSERIAL(SERIAL_PORT) -#else - #define MYSERIAL1 MSERIAL(1) // dummy port - static_assert(false, "SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") -#endif - -#ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == -1 - #define MYSERIAL2 UsbSerial - #elif WITHIN(SERIAL_PORT_2, 1, NUM_UARTS) - #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) - #else - #define MYSERIAL2 MSERIAL(1) // dummy port - static_assert(false, "SERIAL_PORT_2 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") - #endif -#endif - -#ifdef SERIAL_PORT_3 - #if SERIAL_PORT_3 == -1 - #define MYSERIAL3 UsbSerial - #elif WITHIN(SERIAL_PORT_3, 1, NUM_UARTS) - #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) - #else - #define MYSERIAL3 MSERIAL(1) // dummy port - static_assert(false, "SERIAL_PORT_3 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") - #endif -#endif - -#ifdef MMU2_SERIAL_PORT - #if MMU2_SERIAL_PORT == -1 - #define MMU2_SERIAL UsbSerial - #elif WITHIN(MMU2_SERIAL_PORT, 1, NUM_UARTS) - #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) - #else - #define MMU2_SERIAL MSERIAL(1) // dummy port - static_assert(false, "MMU2_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") - #endif -#endif - -#ifdef LCD_SERIAL_PORT - #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL UsbSerial - #elif WITHIN(LCD_SERIAL_PORT, 1, NUM_UARTS) - #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) - #else - #define LCD_SERIAL MSERIAL(1) // dummy port - static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") - #endif - #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() - #endif -#endif +#include "MarlinSerial.h" /** * TODO: review this to return 1 for pins that are not analog input */ #ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) (p) + #define analogInputToDigitalPin(p) pin_t(p) #endif #ifndef digitalPinHasPWM @@ -190,7 +114,7 @@ typedef int8_t pin_t; #define HAL_ADC_RESOLUTION 12 #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 uint16_t analogRead(const pin_t pin); // need hal.adc_enable() first void analogWrite(const pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? @@ -205,7 +129,9 @@ void analogWrite(const pin_t pin, int pwm_val8); // PWM only! mul by 257 in mapl #define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) #define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) -#define PLATFORM_M997_SUPPORT +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif void flashFirmware(const int16_t); #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment @@ -220,10 +146,10 @@ void flashFirmware(const int16_t); // Memory related #define __bss_end __bss_end__ -void _delay_ms(const int ms); - extern "C" char* _sbrk(int incr); +void NVIC_SetPriorityGrouping(uint32_t PriorityGroup); + #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" @@ -261,7 +187,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset @@ -307,3 +233,49 @@ public: static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); }; + +// ------------------------ +// Types +// ------------------------ + +#define __I +#define __IO volatile + typedef struct { + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5]; + __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ + } SCB_Type; + +// ------------------------ +// System Control Space +// ------------------------ + +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ diff --git a/Marlin/src/HAL/STM32F1/HAL_N32.cpp b/Marlin/src/HAL/STM32F1/HAL_N32.cpp new file mode 100644 index 0000000000..e45cbbbfff --- /dev/null +++ b/Marlin/src/HAL/STM32F1/HAL_N32.cpp @@ -0,0 +1,641 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) + * Specifically for VOXELAB_N32. TODO: Rework for generic N32 MCU. + */ + +#if defined(__STM32F1__) && defined(VOXELAB_N32) + +#include "../../inc/MarlinConfig.h" +#include "HAL_N32.h" +#include "HAL.h" + +#include "adc.h" + +void ADC_Init(ADC_Module* NS_ADCx, ADC_InitType* ADC_InitStruct) { + uint32_t tmpreg1 = 0; + uint8_t tmpreg2 = 0; + + /*---------------------------- ADCx CTRL1 Configuration -----------------*/ + /* Get the ADCx CTRL1 value */ + tmpreg1 = NS_ADCx->CTRL1; + /* Clear DUALMOD and SCAN bits */ + tmpreg1 &= CTRL1_CLR_MASK; + /* Configure ADCx: Dual mode and scan conversion mode */ + /* Set DUALMOD bits according to WorkMode value */ + /* Set SCAN bit according to MultiChEn value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->WorkMode | ((uint32_t)ADC_InitStruct->MultiChEn << 8)); + /* Write to ADCx CTRL1 */ + NS_ADCx->CTRL1 = tmpreg1; + + /*---------------------------- ADCx CTRL2 Configuration -----------------*/ + /* Get the ADCx CTRL2 value */ + tmpreg1 = NS_ADCx->CTRL2; + /* Clear CONT, ALIGN and EXTSEL bits */ + tmpreg1 &= CTRL2_CLR_MASK; + /* Configure ADCx: external trigger event and continuous conversion mode */ + /* Set ALIGN bit according to DatAlign value */ + /* Set EXTSEL bits according to ExtTrigSelect value */ + /* Set CONT bit according to ContinueConvEn value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->DatAlign | ADC_InitStruct->ExtTrigSelect + | ((uint32_t)ADC_InitStruct->ContinueConvEn << 1)); + /* Write to ADCx CTRL2 */ + NS_ADCx->CTRL2 = tmpreg1; + + /*---------------------------- ADCx RSEQ1 Configuration -----------------*/ + /* Get the ADCx RSEQ1 value */ + tmpreg1 = NS_ADCx->RSEQ1; + /* Clear L bits */ + tmpreg1 &= RSEQ1_CLR_MASK; + /* Configure ADCx: regular channel sequence length */ + /* Set L bits according to ChsNumber value */ + tmpreg2 |= (uint8_t)(ADC_InitStruct->ChsNumber - (uint8_t)1); + tmpreg1 |= (uint32_t)tmpreg2 << 20; + /* Write to ADCx RSEQ1 */ + NS_ADCx->RSEQ1 = tmpreg1; +} + +/**================================================================ + * ADC reset + ================================================================*/ +void ADC_DeInit(ADC_Module* NS_ADCx) { + uint32_t reg_temp; + + if (NS_ADCx == NS_ADC1) { + /* Enable ADC1 reset state */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= RCC_AHB_PERIPH_ADC1; + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST = 0x00000000; // ADC module reset and clear + } + else if (NS_ADCx == NS_ADC2) { + /* Enable ADC2 reset state */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= RCC_AHB_PERIPH_ADC2; + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST = 0x00000000; // ADC module reset and clear + } + else if (NS_ADCx == NS_ADC3) { + /* Enable ADC2 reset state */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= RCC_AHB_PERIPH_ADC3; + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST = 0x00000000; // ADC module reset and clear + } + else if (NS_ADCx == NS_ADC4) { + /* Enable ADC3 reset state */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= RCC_AHB_PERIPH_ADC4; + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST = 0x00000000; // ADC module reset and clear + } +} + +/**================================================================ + * ADC module enable + ================================================================*/ +void ADC_Enable(ADC_Module* NS_ADCx, uint32_t Cmd) { + if (Cmd) + /* Set the AD_ON bit to wake up the ADC from power down mode */ + NS_ADCx->CTRL2 |= CTRL2_AD_ON_SET; + else + /* Disable the selected ADC peripheral */ + NS_ADCx->CTRL2 &= CTRL2_AD_ON_RESET; +} + +/**================================================================ + * Get the ADC status logo bit + ================================================================*/ +uint32_t ADC_GetFlagStatusNew(ADC_Module* NS_ADCx, uint8_t ADC_FLAG_NEW) { + uint32_t bitstatus = 0; + + /* Check the status of the specified ADC flag */ + if ((NS_ADCx->CTRL3 & ADC_FLAG_NEW) != (uint8_t)0) + /* ADC_FLAG_NEW is set */ + bitstatus = 1; + else + /* ADC_FLAG_NEW is reset */ + bitstatus = 0; + /* Return the ADC_FLAG_NEW status */ + return bitstatus; +} + +/**================================================================ + * Open ADC calibration + ================================================================*/ +void ADC_StartCalibration(ADC_Module* NS_ADCx) { + /* Enable the selected ADC calibration process */ + if (NS_ADCx->CALFACT == 0) + NS_ADCx->CTRL2 |= CTRL2_CAL_SET; +} + +/**================================================================ + * Enable ADC DMA + ================================================================*/ +void ADC_EnableDMA(ADC_Module* NS_ADCx, uint32_t Cmd) { + if (Cmd != 0) + /* Enable the selected ADC DMA request */ + NS_ADCx->CTRL2 |= CTRL2_DMA_SET; + else + /* Disable the selected ADC DMA request */ + NS_ADCx->CTRL2 &= CTRL2_DMA_RESET; +} + +/**================================================================ + * Configure ADC interrupt enable enable + ================================================================*/ +void ADC_ConfigInt(ADC_Module* NS_ADCx, uint16_t ADC_IT, uint32_t Cmd) { + uint8_t itmask = 0; + + /* Get the ADC IT index */ + itmask = (uint8_t)ADC_IT; + if (Cmd != 0) + /* Enable the selected ADC interrupts */ + NS_ADCx->CTRL1 |= itmask; + else + /* Disable the selected ADC interrupts */ + NS_ADCx->CTRL1 &= (~(uint32_t)itmask); +} + +/**================================================================ + * Get ADC calibration status + ================================================================*/ +uint32_t ADC_GetCalibrationStatus(ADC_Module* NS_ADCx) { + uint32_t bitstatus = 0; + + /* Check the status of CAL bit */ + if ((NS_ADCx->CTRL2 & CTRL2_CAL_SET) != (uint32_t)0) + /* CAL bit is set: calibration on going */ + bitstatus = 1; + else + /* CAL bit is reset: end of calibration */ + bitstatus = 0; + + if (NS_ADCx->CALFACT != 0) + bitstatus = 0; + /* Return the CAL bit status */ + return bitstatus; +} + +/**================================================================ + * Configure the ADC channel + ================================================================*/ +void ADC_ConfigRegularChannel(ADC_Module* NS_ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) { + uint32_t tmpreg1 = 0, tmpreg2 = 0; + + if (ADC_Channel == ADC_CH_18) { + tmpreg1 = NS_ADCx->SAMPT3; + tmpreg1 &= (~0x00000007); + tmpreg1 |= ADC_SampleTime; + NS_ADCx->SAMPT3 = tmpreg1; + } + else if (ADC_Channel > ADC_CH_9) { /* if ADC_CH_10 ... ADC_CH_17 is selected */ + /* Get the old register value */ + tmpreg1 = NS_ADCx->SAMPT1; + /* Calculate the mask to clear */ + tmpreg2 = SAMPT1_SMP_SET << (3 * (ADC_Channel - 10)); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10)); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->SAMPT1 = tmpreg1; + } + else { /* ADC_Channel include in ADC_Channel_[0..9] */ + /* Get the old register value */ + tmpreg1 = NS_ADCx->SAMPT2; + /* Calculate the mask to clear */ + tmpreg2 = SAMPT2_SMP_SET << (3 * ADC_Channel); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->SAMPT2 = tmpreg1; + } + /* For Rank 1 to 6 */ + if (Rank < 7) { + /* Get the old register value */ + tmpreg1 = NS_ADCx->RSEQ3; + /* Calculate the mask to clear */ + tmpreg2 = SQR3_SEQ_SET << (5 * (Rank - 1)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->RSEQ3 = tmpreg1; + } + /* For Rank 7 to 12 */ + else if (Rank < 13) { + /* Get the old register value */ + tmpreg1 = NS_ADCx->RSEQ2; + /* Calculate the mask to clear */ + tmpreg2 = SQR2_SEQ_SET << (5 * (Rank - 7)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->RSEQ2 = tmpreg1; + } + /* For Rank 13 to 16 */ + else { + /* Get the old register value */ + tmpreg1 = NS_ADCx->RSEQ1; + /* Calculate the mask to clear */ + tmpreg2 = SQR1_SEQ_SET << (5 * (Rank - 13)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->RSEQ1 = tmpreg1; + } +} + +/**================================================================ + * Start ADC conversion + ================================================================*/ +void ADC_EnableSoftwareStartConv(ADC_Module* NS_ADCx, uint32_t Cmd) { + if (Cmd != 0) + /* Enable the selected ADC conversion on external event and start the selected + ADC conversion */ + NS_ADCx->CTRL2 |= CTRL2_EXT_TRIG_SWSTART_SET; + else + /* Disable the selected ADC conversion on external event and stop the selected + ADC conversion */ + NS_ADCx->CTRL2 &= CTRL2_EXT_TRIG_SWSTART_RESET; +} + +/**================================================================ + * Get the ADC status logo bit + ================================================================*/ +uint32_t ADC_GetFlagStatus(ADC_Module* NS_ADCx, uint8_t ADC_FLAG) { + uint32_t bitstatus = 0; + + /* Check the status of the specified ADC flag */ + if ((NS_ADCx->STS & ADC_FLAG) != (uint8_t)0) + /* ADC_FLAG is set */ + bitstatus = 1; + else + /* ADC_FLAG is reset */ + bitstatus = 0; + /* Return the ADC_FLAG status */ + return bitstatus; +} + +/**================================================================ + * Clear status logo bit + ================================================================*/ +void ADC_ClearFlag(ADC_Module* NS_ADCx, uint8_t ADC_FLAG) { + /* Clear the selected ADC flags */ + NS_ADCx->STS &= ~(uint32_t)ADC_FLAG; +} + +/**================================================================ + * Get ADC sampling value + ================================================================*/ +uint16_t ADC_GetDat(ADC_Module* NS_ADCx) { + /* Return the selected ADC conversion value */ + return (uint16_t)NS_ADCx->DAT; +} + +/**================================================================ + * Initialize ADC clock + ================================================================*/ + +void enable_adc_clk(uint8_t cmd) { + uint32_t reg_temp; + if (cmd) { + /** Make PWR clock */ + reg_temp = ADC_RCC_APB1PCLKEN; + reg_temp |= RCC_APB1Periph_PWR; + ADC_RCC_APB1PCLKEN = reg_temp; + + /** Enable expansion mode */ + reg_temp = NS_PWR_CR3; + reg_temp |= 0x00000001; + NS_PWR_CR3 = reg_temp; + + /** Make ADC clock */ + reg_temp = ADC_RCC_AHBPCLKEN; + reg_temp |= ( RCC_AHB_PERIPH_ADC1 | + RCC_AHB_PERIPH_ADC2 | + RCC_AHB_PERIPH_ADC3 | + RCC_AHB_PERIPH_ADC4 ); + ADC_RCC_AHBPCLKEN = reg_temp; + + /** Reset */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= ( RCC_AHB_PERIPH_ADC1 | + RCC_AHB_PERIPH_ADC2 | + RCC_AHB_PERIPH_ADC3 | + RCC_AHB_PERIPH_ADC4 ); + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST &= ~reg_temp; // ADC module reset and clear + + /** Set ADC 1M clock */ + reg_temp = ADC_RCC_CFG2; + reg_temp &= CFG2_ADC1MSEL_RESET_MASK; // HSI as an ADC 1M clock + reg_temp &= CFG2_ADC1MPRES_RESET_MASK; + reg_temp |= 7 << 11; // Adc1m 8m / 8 = 1m + + /** Set the ADC PLL frequency split coefficient */ + reg_temp &= CFG2_ADCPLLPRES_RESET_MASK; + reg_temp |= RCC_ADCPLLCLK_DIV4; // ADC PLL frequency split coefficient + + /** Set the ADC HCLK frequency frequency coefficient */ + reg_temp &= CFG2_ADCHPRES_RESET_MASK; + reg_temp |= RCC_ADCHCLK_DIV4; // ADC HCLK frequency split coefficient + ADC_RCC_CFG2 = reg_temp; // Write to register + } + else { + /** Turn off the ADC clock */ + reg_temp = ADC_RCC_AHBPCLKEN; + reg_temp &= ~( RCC_AHB_PERIPH_ADC1 | + RCC_AHB_PERIPH_ADC2 | + RCC_AHB_PERIPH_ADC3 | + RCC_AHB_PERIPH_ADC4 ); + ADC_RCC_AHBPCLKEN = reg_temp; + } + +} + +/**================================================================ + * Initialize ADC peripheral parameters + ================================================================*/ +void ADC_Initial(ADC_Module* NS_ADCx) { + ADC_InitType ADC_InitStructure; + + /* ADC configuration ------------------------------------------------------*/ + ADC_InitStructure.WorkMode = ADC_WORKMODE_INDEPENDENT; // Independent mode + ADC_InitStructure.MultiChEn = 1; // Multi-channel enable + ADC_InitStructure.ContinueConvEn = 1; // Continuous enable + ADC_InitStructure.ExtTrigSelect = ADC_EXT_TRIGCONV_NONE; // Non-trigger + ADC_InitStructure.DatAlign = ADC_DAT_ALIGN_R; // Right alignment + ADC_InitStructure.ChsNumber = 2; // Scan channel number + ADC_Init(NS_ADCx, &ADC_InitStructure); + + /* ADC regular channel14 configuration */ + ADC_ConfigRegularChannel(NS_ADCx, ADC2_Channel_05_PC4, 2, ADC_SAMP_TIME_55CYCLES5); + ADC_ConfigRegularChannel(NS_ADCx, ADC2_Channel_12_PC5, 1, ADC_SAMP_TIME_55CYCLES5); + + /** 使能ADC DMA */ + ADC_EnableDMA(NS_ADCx, 1); + + /* Enable ADC */ + ADC_Enable(NS_ADCx, 1); + while(ADC_GetFlagStatusNew(NS_ADCx, ADC_FLAG_RDY) == 0); + + /* Start ADC calibration */ + ADC_StartCalibration(NS_ADCx); + while (ADC_GetCalibrationStatus(NS_ADCx)); + + /* Start ADC Software Conversion */ + ADC_EnableSoftwareStartConv(NS_ADCx, 1); +} + +/**================================================================ + * Single independent sampling + ================================================================*/ +uint16_t ADC_GetData(ADC_Module* NS_ADCx, uint8_t ADC_Channel) { + uint16_t dat; + + /** Set channel parameters */ + ADC_ConfigRegularChannel(NS_ADCx, ADC_Channel, 1, ADC_SAMP_TIME_239CYCLES5); + + /* Start ADC Software Conversion */ + ADC_EnableSoftwareStartConv(NS_ADCx, 1); + while(ADC_GetFlagStatus(NS_ADCx, ADC_FLAG_ENDC) == 0); + + ADC_ClearFlag(NS_ADCx, ADC_FLAG_ENDC); + ADC_ClearFlag(NS_ADCx, ADC_FLAG_STR); + dat = ADC_GetDat(NS_ADCx); + return dat; +} + +void DMA_DeInit(DMA_ChannelType* DMAyChx) { + + /* Disable the selected DMAy Channelx */ + DMAyChx->CHCFG &= (uint16_t)(~DMA_CHCFG1_CHEN); + + /* Reset DMAy Channelx control register */ + DMAyChx->CHCFG = 0; + + /* Reset DMAy Channelx remaining bytes register */ + DMAyChx->TXNUM = 0; + + /* Reset DMAy Channelx peripheral address register */ + DMAyChx->PADDR = 0; + + /* Reset DMAy Channelx memory address register */ + DMAyChx->MADDR = 0; + + if (DMAyChx == DMA1_CH1) { + /* Reset interrupt pending bits for DMA1 Channel1 */ + DMA1->INTCLR |= DMA1_CH1_INT_MASK; + } + else if (DMAyChx == DMA1_CH2) { + /* Reset interrupt pending bits for DMA1 Channel2 */ + DMA1->INTCLR |= DMA1_CH2_INT_MASK; + } + else if (DMAyChx == DMA1_CH3) { + /* Reset interrupt pending bits for DMA1 Channel3 */ + DMA1->INTCLR |= DMA1_CH3_INT_MASK; + } + else if (DMAyChx == DMA1_CH4) { + /* Reset interrupt pending bits for DMA1 Channel4 */ + DMA1->INTCLR |= DMA1_CH4_INT_MASK; + } + else if (DMAyChx == DMA1_CH5) { + /* Reset interrupt pending bits for DMA1 Channel5 */ + DMA1->INTCLR |= DMA1_CH5_INT_MASK; + } + else if (DMAyChx == DMA1_CH6) { + /* Reset interrupt pending bits for DMA1 Channel6 */ + DMA1->INTCLR |= DMA1_CH6_INT_MASK; + } + else if (DMAyChx == DMA1_CH7) { + /* Reset interrupt pending bits for DMA1 Channel7 */ + DMA1->INTCLR |= DMA1_CH7_INT_MASK; + } + else if (DMAyChx == DMA1_CH8) { + /* Reset interrupt pending bits for DMA1 Channel8 */ + DMA1->INTCLR |= DMA1_CH8_INT_MASK; + } + else if (DMAyChx == DMA2_CH1) { + /* Reset interrupt pending bits for DMA2 Channel1 */ + DMA2->INTCLR |= DMA2_CH1_INT_MASK; + } + else if (DMAyChx == DMA2_CH2) { + /* Reset interrupt pending bits for DMA2 Channel2 */ + DMA2->INTCLR |= DMA2_CH2_INT_MASK; + } + else if (DMAyChx == DMA2_CH3) { + /* Reset interrupt pending bits for DMA2 Channel3 */ + DMA2->INTCLR |= DMA2_CH3_INT_MASK; + } + else if (DMAyChx == DMA2_CH4) { + /* Reset interrupt pending bits for DMA2 Channel4 */ + DMA2->INTCLR |= DMA2_CH4_INT_MASK; + } + else if (DMAyChx == DMA2_CH5) { + /* Reset interrupt pending bits for DMA2 Channel5 */ + DMA2->INTCLR |= DMA2_CH5_INT_MASK; + } + else if (DMAyChx == DMA2_CH6) { + /* Reset interrupt pending bits for DMA2 Channel6 */ + DMA2->INTCLR |= DMA2_CH6_INT_MASK; + } + else if (DMAyChx == DMA2_CH7) { + /* Reset interrupt pending bits for DMA2 Channel7 */ + DMA2->INTCLR |= DMA2_CH7_INT_MASK; + } + else if (DMAyChx == DMA2_CH8) + /* Reset interrupt pending bits for DMA2 Channel8 */ + DMA2->INTCLR |= DMA2_CH8_INT_MASK; +} + +void DMA_Init(DMA_ChannelType* DMAyChx, DMA_InitType* DMA_InitParam) { + uint32_t tmpregister = 0; + + /*--------------------------- DMAy Channelx CHCFG Configuration --------------*/ + /* Get the DMAyChx CHCFG value */ + tmpregister = DMAyChx->CHCFG; + /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */ + tmpregister &= CCR_CLEAR_Mask; + /* Configure DMAy Channelx: data transfer, data size, priority level and mode */ + /* Set DIR bit according to Direction value */ + /* Set CIRC bit according to CircularMode value */ + /* Set PINC bit according to PeriphInc value */ + /* Set MINC bit according to DMA_MemoryInc value */ + /* Set PSIZE bits according to PeriphDataSize value */ + /* Set MSIZE bits according to MemDataSize value */ + /* Set PL bits according to Priority value */ + /* Set the MEM2MEM bit according to Mem2Mem value */ + tmpregister |= DMA_InitParam->Direction | DMA_InitParam->CircularMode | DMA_InitParam->PeriphInc + | DMA_InitParam->DMA_MemoryInc | DMA_InitParam->PeriphDataSize | DMA_InitParam->MemDataSize + | DMA_InitParam->Priority | DMA_InitParam->Mem2Mem; + + /* Write to DMAy Channelx CHCFG */ + DMAyChx->CHCFG = tmpregister; + + /*--------------------------- DMAy Channelx TXNUM Configuration --------------*/ + /* Write to DMAy Channelx TXNUM */ + DMAyChx->TXNUM = DMA_InitParam->BufSize; + + /*--------------------------- DMAy Channelx PADDR Configuration --------------*/ + /* Write to DMAy Channelx PADDR */ + DMAyChx->PADDR = DMA_InitParam->PeriphAddr; + + /*--------------------------- DMAy Channelx MADDR Configuration --------------*/ + /* Write to DMAy Channelx MADDR */ + DMAyChx->MADDR = DMA_InitParam->MemAddr; +} + +void DMA_EnableChannel(DMA_ChannelType* DMAyChx, uint32_t Cmd) { + if (Cmd != 0) { + /* Enable the selected DMAy Channelx */ + DMAyChx->CHCFG |= DMA_CHCFG1_CHEN; + } + else { + /* Disable the selected DMAy Channelx */ + DMAyChx->CHCFG &= (uint16_t)(~DMA_CHCFG1_CHEN); + } +} + +/**================================================================ + * Initialize the DMA of ADC + ================================================================*/ +void ADC_DMA_init() { + DMA_InitType DMA_InitStructure; + uint32_t reg_temp; + + /** Make DMA clock */ + reg_temp = ADC_RCC_AHBPCLKEN; + reg_temp |= ( RCC_AHB_PERIPH_DMA1 | + RCC_AHB_PERIPH_DMA2 ); + ADC_RCC_AHBPCLKEN = reg_temp; + + /* DMA channel configuration*/ + DMA_DeInit(USE_DMA_CH); + DMA_InitStructure.PeriphAddr = (uint32_t)&USE_ADC->DAT; + DMA_InitStructure.MemAddr = (uint32_t)adc_results; + DMA_InitStructure.Direction = DMA_DIR_PERIPH_SRC; // Peripheral-> memory + DMA_InitStructure.BufSize = 2; + DMA_InitStructure.PeriphInc = DMA_PERIPH_INC_DISABLE; + DMA_InitStructure.DMA_MemoryInc = DMA_MEM_INC_ENABLE; // Memory ++ + DMA_InitStructure.PeriphDataSize = DMA_PERIPH_DATA_SIZE_HALFWORD; + DMA_InitStructure.MemDataSize = DMA_MemoryDataSize_HalfWord; + DMA_InitStructure.CircularMode = DMA_MODE_CIRCULAR; + DMA_InitStructure.Priority = DMA_PRIORITY_HIGH; + DMA_InitStructure.Mem2Mem = DMA_M2M_DISABLE; + DMA_Init(USE_DMA_CH, &DMA_InitStructure); + + /* Enable DMA channel1 */ + DMA_EnableChannel(USE_DMA_CH, 1); +} + +/**============================================================================= + * n32g452 - end + ==============================================================================*/ + +#define NS_PINRT(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0) + +// Init the AD in continuous capture mode +void MarlinHAL::adc_init() { + uint32_t reg_temp; + + //SERIAL_ECHO_MSG("\r\n n32g45x HAL_adc_init\r\n"); + + // GPIO settings + reg_temp = ADC_RCC_APB2PCLKEN; + reg_temp |= 0x0F; // Make PORT mouth clock + ADC_RCC_APB2PCLKEN = reg_temp; + + //reg_temp = NS_GPIOC_PL_CFG; + //reg_temp &= 0XFF00FFFF; + //NS_GPIOC_PL_CFG = reg_temp; // PC4/5 analog input + + enable_adc_clk(1); // Make ADC clock + ADC_DMA_init(); // DMA initialization + ADC_Initial(NS_ADC2); // ADC initialization + + delay(2); + //NS_PINRT("get adc1 = ", adc_results[0], "\r\n"); + //NS_PINRT("get adc2 = ", adc_results[1], "\r\n"); +} + +#endif // __STM32F1__ && VOXELAB_N32 diff --git a/Marlin/src/HAL/STM32F1/HAL_N32.h b/Marlin/src/HAL/STM32F1/HAL_N32.h new file mode 100644 index 0000000000..719368f6f1 --- /dev/null +++ b/Marlin/src/HAL/STM32F1/HAL_N32.h @@ -0,0 +1,891 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) + * Specifically for VOXELAB_N32 (N32G452). TODO: Rework for generic N32 MCU. + */ + +#include + +typedef struct { + uint32_t WorkMode; + uint32_t MultiChEn; + uint32_t ContinueConvEn; + uint32_t ExtTrigSelect; + uint32_t DatAlign; + uint8_t ChsNumber; +} ADC_InitType; + +typedef struct { + __IO uint32_t STS; + __IO uint32_t CTRL1; + __IO uint32_t CTRL2; + __IO uint32_t SAMPT1; + __IO uint32_t SAMPT2; + __IO uint32_t JOFFSET1; + __IO uint32_t JOFFSET2; + __IO uint32_t JOFFSET3; + __IO uint32_t JOFFSET4; + __IO uint32_t WDGHIGH; + __IO uint32_t WDGLOW; + __IO uint32_t RSEQ1; + __IO uint32_t RSEQ2; + __IO uint32_t RSEQ3; + __IO uint32_t JSEQ; + __IO uint32_t JDAT1; + __IO uint32_t JDAT2; + __IO uint32_t JDAT3; + __IO uint32_t JDAT4; + __IO uint32_t DAT; + __IO uint32_t DIFSEL; + __IO uint32_t CALFACT; + __IO uint32_t CTRL3; + __IO uint32_t SAMPT3; +} ADC_Module; + +#define NS_ADC1_BASE ((uint32_t)0x40020800) +#define NS_ADC2_BASE ((uint32_t)0x40020c00) +#define NS_ADC3_BASE ((uint32_t)0x40021800) +#define NS_ADC4_BASE ((uint32_t)0x40021c00) + +#define NS_ADC1 ((ADC_Module*)NS_ADC1_BASE) +#define NS_ADC2 ((ADC_Module*)NS_ADC2_BASE) +#define NS_ADC3 ((ADC_Module*)NS_ADC3_BASE) +#define NS_ADC4 ((ADC_Module*)NS_ADC4_BASE) + +#define ADC1_Channel_01_PA0 ((uint8_t)0x01) +#define ADC1_Channel_02_PA1 ((uint8_t)0x02) +#define ADC1_Channel_03_PA6 ((uint8_t)0x03) +#define ADC1_Channel_04_PA3 ((uint8_t)0x04) +#define ADC1_Channel_05_PF4 ((uint8_t)0x05) +#define ADC1_Channel_06_PC0 ((uint8_t)0x06) +#define ADC1_Channel_07_PC1 ((uint8_t)0x07) +#define ADC1_Channel_08_PC2 ((uint8_t)0x08) +#define ADC1_Channel_09_PC3 ((uint8_t)0x09) +#define ADC1_Channel_10_PF2 ((uint8_t)0x0A) +#define ADC1_Channel_11_PA2 ((uint8_t)0x0B) + +#define ADC2_Channel_01_PA4 ((uint8_t)0x01) +#define ADC2_Channel_02_PA5 ((uint8_t)0x02) +#define ADC2_Channel_03_PB1 ((uint8_t)0x03) +#define ADC2_Channel_04_PA7 ((uint8_t)0x04) +#define ADC2_Channel_05_PC4 ((uint8_t)0x05) +#define ADC2_Channel_06_PC0 ((uint8_t)0x06) +#define ADC2_Channel_07_PC1 ((uint8_t)0x07) +#define ADC2_Channel_08_PC2 ((uint8_t)0x08) +#define ADC2_Channel_09_PC3 ((uint8_t)0x09) +#define ADC2_Channel_10_PF2 ((uint8_t)0x0A) +#define ADC2_Channel_11_PA2 ((uint8_t)0x0B) +#define ADC2_Channel_12_PC5 ((uint8_t)0x0C) +#define ADC2_Channel_13_PB2 ((uint8_t)0x0D) + +#define ADC3_Channel_01_PB11 ((uint8_t)0x01) +#define ADC3_Channel_02_PE9 ((uint8_t)0x02) +#define ADC3_Channel_03_PE13 ((uint8_t)0x03) +#define ADC3_Channel_04_PE12 ((uint8_t)0x04) +#define ADC3_Channel_05_PB13 ((uint8_t)0x05) +#define ADC3_Channel_06_PE8 ((uint8_t)0x06) +#define ADC3_Channel_07_PD10 ((uint8_t)0x07) +#define ADC3_Channel_08_PD11 ((uint8_t)0x08) +#define ADC3_Channel_09_PD12 ((uint8_t)0x09) +#define ADC3_Channel_10_PD13 ((uint8_t)0x0A) +#define ADC3_Channel_11_PD14 ((uint8_t)0x0B) +#define ADC3_Channel_12_PB0 ((uint8_t)0x0C) +#define ADC3_Channel_13_PE7 ((uint8_t)0x0D) +#define ADC3_Channel_14_PE10 ((uint8_t)0x0E) +#define ADC3_Channel_15_PE11 ((uint8_t)0x0F) + +#define ADC4_Channel_01_PE14 ((uint8_t)0x01) +#define ADC4_Channel_02_PE15 ((uint8_t)0x02) +#define ADC4_Channel_03_PB12 ((uint8_t)0x03) +#define ADC4_Channel_04_PB14 ((uint8_t)0x04) +#define ADC4_Channel_05_PB15 ((uint8_t)0x05) +#define ADC4_Channel_06_PE8 ((uint8_t)0x06) +#define ADC4_Channel_07_PD10 ((uint8_t)0x07) +#define ADC4_Channel_08_PD11 ((uint8_t)0x08) +#define ADC4_Channel_09_PD12 ((uint8_t)0x09) +#define ADC4_Channel_10_PD13 ((uint8_t)0x0A) +#define ADC4_Channel_11_PD14 ((uint8_t)0x0B) +#define ADC4_Channel_12_PD8 ((uint8_t)0x0C) +#define ADC4_Channel_13_PD9 ((uint8_t)0x0D) + +#define ADC_RCC_BASE ((uint32_t)0x40021000) +#define ADC_RCC_CTRL *((uint32_t*)(ADC_RCC_BASE + 0x00)) +#define ADC_RCC_CFG *((uint32_t*)(ADC_RCC_BASE + 0x04)) +#define ADC_RCC_CLKINT *((uint32_t*)(ADC_RCC_BASE + 0x08)) +#define ADC_RCC_APB2PRST *((uint32_t*)(ADC_RCC_BASE + 0x0c)) +#define ADC_RCC_APB1PRST *((uint32_t*)(ADC_RCC_BASE + 0x10)) +#define ADC_RCC_AHBPCLKEN *((uint32_t*)(ADC_RCC_BASE + 0x14)) +#define ADC_RCC_APB2PCLKEN *((uint32_t*)(ADC_RCC_BASE + 0x18)) +#define ADC_RCC_APB1PCLKEN *((uint32_t*)(ADC_RCC_BASE + 0x1c)) +#define ADC_RCC_BDCTRL *((uint32_t*)(ADC_RCC_BASE + 0x20)) +#define ADC_RCC_CTRLSTS *((uint32_t*)(ADC_RCC_BASE + 0x24)) +#define ADC_RCC_AHBPRST *((uint32_t*)(ADC_RCC_BASE + 0x28)) +#define ADC_RCC_CFG2 *((uint32_t*)(ADC_RCC_BASE + 0x2c)) +#define ADC_RCC_CFG3 *((uint32_t*)(ADC_RCC_BASE + 0x30)) + +#define NS_PWR_CR3 *((uint32_t*)(0x40007000 + 0x0C)) +#define RCC_APB1Periph_PWR ((uint32_t)0x10000000) + +/////////////////////////////// +#define NS_GPIOA_BASE ((uint32_t)0x40010800) +#define NS_GPIOA_PL_CFG *((uint32_t*)(NS_GPIOA_BASE + 0x00)) +#define NS_GPIOA_PH_CFG *((uint32_t*)(NS_GPIOA_BASE + 0x04)) + +#define NS_GPIOC_BASE ((uint32_t)0x40011000) +#define NS_GPIOC_PL_CFG *((uint32_t*)(NS_GPIOC_BASE + 0x00)) +#define NS_GPIOC_PH_CFG *((uint32_t*)(NS_GPIOC_BASE + 0x04)) + +/* CFG2 register bit mask */ +#define CFG2_TIM18CLKSEL_SET_MASK ((uint32_t)0x20000000) +#define CFG2_TIM18CLKSEL_RESET_MASK ((uint32_t)0xDFFFFFFF) +#define CFG2_RNGCPRES_SET_MASK ((uint32_t)0x1F000000) +#define CFG2_RNGCPRES_RESET_MASK ((uint32_t)0xE0FFFFFF) +#define CFG2_ADC1MSEL_SET_MASK ((uint32_t)0x00000400) +#define CFG2_ADC1MSEL_RESET_MASK ((uint32_t)0xFFFFFBFF) +#define CFG2_ADC1MPRES_SET_MASK ((uint32_t)0x0000F800) +#define CFG2_ADC1MPRES_RESET_MASK ((uint32_t)0xFFFF07FF) +#define CFG2_ADCPLLPRES_SET_MASK ((uint32_t)0x000001F0) +#define CFG2_ADCPLLPRES_RESET_MASK ((uint32_t)0xFFFFFE0F) +#define CFG2_ADCHPRES_SET_MASK ((uint32_t)0x0000000F) +#define CFG2_ADCHPRES_RESET_MASK ((uint32_t)0xFFFFFFF0) + +#define RCC_ADCPLLCLK_DISABLE ((uint32_t)0xFFFFFEFF) +#define RCC_ADCPLLCLK_DIV1 ((uint32_t)0x00000100) +#define RCC_ADCPLLCLK_DIV2 ((uint32_t)0x00000110) +#define RCC_ADCPLLCLK_DIV4 ((uint32_t)0x00000120) +#define RCC_ADCPLLCLK_DIV6 ((uint32_t)0x00000130) +#define RCC_ADCPLLCLK_DIV8 ((uint32_t)0x00000140) +#define RCC_ADCPLLCLK_DIV10 ((uint32_t)0x00000150) +#define RCC_ADCPLLCLK_DIV12 ((uint32_t)0x00000160) +#define RCC_ADCPLLCLK_DIV16 ((uint32_t)0x00000170) +#define RCC_ADCPLLCLK_DIV32 ((uint32_t)0x00000180) +#define RCC_ADCPLLCLK_DIV64 ((uint32_t)0x00000190) +#define RCC_ADCPLLCLK_DIV128 ((uint32_t)0x000001A0) +#define RCC_ADCPLLCLK_DIV256 ((uint32_t)0x000001B0) +#define RCC_ADCPLLCLK_DIV_OTHERS ((uint32_t)0x000001C0) + +#define RCC_ADCHCLK_DIV1 ((uint32_t)0x00000000) +#define RCC_ADCHCLK_DIV2 ((uint32_t)0x00000001) +#define RCC_ADCHCLK_DIV4 ((uint32_t)0x00000002) +#define RCC_ADCHCLK_DIV6 ((uint32_t)0x00000003) +#define RCC_ADCHCLK_DIV8 ((uint32_t)0x00000004) +#define RCC_ADCHCLK_DIV10 ((uint32_t)0x00000005) +#define RCC_ADCHCLK_DIV12 ((uint32_t)0x00000006) +#define RCC_ADCHCLK_DIV16 ((uint32_t)0x00000007) +#define RCC_ADCHCLK_DIV32 ((uint32_t)0x00000008) +#define RCC_ADCHCLK_DIV_OTHERS ((uint32_t)0x00000008) + +#define SAMPT1_SMP_SET ((uint32_t)0x00000007) +#define SAMPT2_SMP_SET ((uint32_t)0x00000007) + +#define SQR4_SEQ_SET ((uint32_t)0x0000001F) +#define SQR3_SEQ_SET ((uint32_t)0x0000001F) +#define SQR2_SEQ_SET ((uint32_t)0x0000001F) +#define SQR1_SEQ_SET ((uint32_t)0x0000001F) + +#define CTRL1_CLR_MASK ((uint32_t)0xFFF0FEFF) +#define RSEQ1_CLR_MASK ((uint32_t)0xFF0FFFFF) +#define CTRL2_CLR_MASK ((uint32_t)0xFFF1F7FD) + +#define ADC_CH_0 ((uint8_t)0x00) +#define ADC_CH_1 ((uint8_t)0x01) +#define ADC_CH_2 ((uint8_t)0x02) +#define ADC_CH_3 ((uint8_t)0x03) +#define ADC_CH_4 ((uint8_t)0x04) +#define ADC_CH_5 ((uint8_t)0x05) +#define ADC_CH_6 ((uint8_t)0x06) +#define ADC_CH_7 ((uint8_t)0x07) +#define ADC_CH_8 ((uint8_t)0x08) +#define ADC_CH_9 ((uint8_t)0x09) +#define ADC_CH_10 ((uint8_t)0x0A) +#define ADC_CH_11 ((uint8_t)0x0B) +#define ADC_CH_12 ((uint8_t)0x0C) +#define ADC_CH_13 ((uint8_t)0x0D) +#define ADC_CH_14 ((uint8_t)0x0E) +#define ADC_CH_15 ((uint8_t)0x0F) +#define ADC_CH_16 ((uint8_t)0x10) +#define ADC_CH_17 ((uint8_t)0x11) +#define ADC_CH_18 ((uint8_t)0x12) + +#define ADC_WORKMODE_INDEPENDENT ((uint32_t)0x00000000) +#define ADC_WORKMODE_REG_INJECT_SIMULT ((uint32_t)0x00010000) +#define ADC_WORKMODE_REG_SIMULT_ALTER_TRIG ((uint32_t)0x00020000) +#define ADC_WORKMODE_INJ_SIMULT_FAST_INTERL ((uint32_t)0x00030000) +#define ADC_WORKMODE_INJ_SIMULT_SLOW_INTERL ((uint32_t)0x00040000) +#define ADC_WORKMODE_INJ_SIMULT ((uint32_t)0x00050000) +#define ADC_WORKMODE_REG_SIMULT ((uint32_t)0x00060000) +#define ADC_WORKMODE_FAST_INTERL ((uint32_t)0x00070000) +#define ADC_WORKMODE_SLOW_INTERL ((uint32_t)0x00080000) +#define ADC_WORKMODE_ALTER_TRIG ((uint32_t)0x00090000) + +#define ADC_EXT_TRIGCONV_T1_CC3 ((uint32_t)0x00040000) //!< For ADC1, ADC2, ADC3, and ADC4 +#define ADC_EXT_TRIGCONV_NONE ((uint32_t)0x000E0000) //!< For ADC1, ADC2, ADC3, and ADC4 + +#define ADC_DAT_ALIGN_R ((uint32_t)0x00000000) +#define ADC_DAT_ALIGN_L ((uint32_t)0x00000800) + +#define ADC_FLAG_RDY ((uint8_t)0x20) +#define ADC_FLAG_PD_RDY ((uint8_t)0x40) + +#define CTRL2_AD_ON_SET ((uint32_t)0x00000001) +#define CTRL2_AD_ON_RESET ((uint32_t)0xFFFFFFFE) + +#define CTRL2_CAL_SET ((uint32_t)0x00000004) + +/* ADC Software start mask */ +#define CTRL2_EXT_TRIG_SWSTART_SET ((uint32_t)0x00500000) +#define CTRL2_EXT_TRIG_SWSTART_RESET ((uint32_t)0xFFAFFFFF) + +#define ADC_SAMP_TIME_1CYCLES5 ((uint8_t)0x00) +#define ADC_SAMP_TIME_7CYCLES5 ((uint8_t)0x01) +#define ADC_SAMP_TIME_13CYCLES5 ((uint8_t)0x02) +#define ADC_SAMP_TIME_28CYCLES5 ((uint8_t)0x03) +#define ADC_SAMP_TIME_41CYCLES5 ((uint8_t)0x04) +#define ADC_SAMP_TIME_55CYCLES5 ((uint8_t)0x05) +#define ADC_SAMP_TIME_71CYCLES5 ((uint8_t)0x06) +#define ADC_SAMP_TIME_239CYCLES5 ((uint8_t)0x07) + +#define ADC_FLAG_AWDG ((uint8_t)0x01) +#define ADC_FLAG_ENDC ((uint8_t)0x02) +#define ADC_FLAG_JENDC ((uint8_t)0x04) +#define ADC_FLAG_JSTR ((uint8_t)0x08) +#define ADC_FLAG_STR ((uint8_t)0x10) +#define ADC_FLAG_EOC_ANY ((uint8_t)0x20) +#define ADC_FLAG_JEOC_ANY ((uint8_t)0x40) + +/* ADC DMA mask */ +#define CTRL2_DMA_SET ((uint32_t)0x00000100) +#define CTRL2_DMA_RESET ((uint32_t)0xFFFFFEFF) + +typedef struct { + uint32_t PeriphAddr; + uint32_t MemAddr; + uint32_t Direction; + uint32_t BufSize; + uint32_t PeriphInc; + uint32_t DMA_MemoryInc; + uint32_t PeriphDataSize; + uint32_t MemDataSize; + uint32_t CircularMode; + uint32_t Priority; + uint32_t Mem2Mem; +} DMA_InitType; + +typedef struct { + __IO uint32_t CHCFG; + __IO uint32_t TXNUM; + __IO uint32_t PADDR; + __IO uint32_t MADDR; + __IO uint32_t CHSEL; +} DMA_ChannelType; + +#define DMA_DIR_PERIPH_DST ((uint32_t)0x00000010) +#define DMA_DIR_PERIPH_SRC ((uint32_t)0x00000000) + +#define DMA_PERIPH_INC_ENABLE ((uint32_t)0x00000040) +#define DMA_PERIPH_INC_DISABLE ((uint32_t)0x00000000) + +#define DMA_MEM_INC_ENABLE ((uint32_t)0x00000080) +#define DMA_MEM_INC_DISABLE ((uint32_t)0x00000000) + +#define DMA_PERIPH_DATA_SIZE_BYTE ((uint32_t)0x00000000) +#define DMA_PERIPH_DATA_SIZE_HALFWORD ((uint32_t)0x00000100) +#define DMA_PERIPH_DATA_SIZE_WORD ((uint32_t)0x00000200) + +#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000) +#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00000400) +#define DMA_MemoryDataSize_Word ((uint32_t)0x00000800) + +#define DMA_MODE_CIRCULAR ((uint32_t)0x00000020) +#define DMA_MODE_NORMAL ((uint32_t)0x00000000) + +#define DMA_M2M_ENABLE ((uint32_t)0x00004000) +#define DMA_M2M_DISABLE ((uint32_t)0x00000000) + +#define RCC_AHB_PERIPH_DMA1 ((uint32_t)0x00000001) +#define RCC_AHB_PERIPH_DMA2 ((uint32_t)0x00000002) + +/******************* Bit definition for DMA_CHCFG1 register *******************/ +#define DMA_CHCFG1_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG1_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG1_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG1_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG1_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG1_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG1_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG1_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define NS_DMA1_BASE (0x40020000) +#define DMA1_CH1_BASE (NS_DMA1_BASE + 0x0008) +#define DMA1_CH2_BASE (NS_DMA1_BASE + 0x001C) +#define DMA1_CH3_BASE (NS_DMA1_BASE + 0x0030) +#define DMA1_CH4_BASE (NS_DMA1_BASE + 0x0044) +#define DMA1_CH5_BASE (NS_DMA1_BASE + 0x0058) +#define DMA1_CH6_BASE (NS_DMA1_BASE + 0x006C) +#define DMA1_CH7_BASE (NS_DMA1_BASE + 0x0080) +#define DMA1_CH8_BASE (NS_DMA1_BASE + 0x0094) + +#define NS_DMA2_BASE (0x40020400) +#define DMA2_CH1_BASE (NS_DMA2_BASE + 0x008) +#define DMA2_CH2_BASE (NS_DMA2_BASE + 0x01C) +#define DMA2_CH3_BASE (NS_DMA2_BASE + 0x0030) +#define DMA2_CH4_BASE (NS_DMA2_BASE + 0x0044) +#define DMA2_CH5_BASE (NS_DMA2_BASE + 0x0058) +#define DMA2_CH6_BASE (NS_DMA2_BASE + 0x006C) +#define DMA2_CH7_BASE (NS_DMA2_BASE + 0x0080) +#define DMA2_CH8_BASE (NS_DMA2_BASE + 0x0094) + +#define DMA1 ((DMA_Module*)NS_DMA1_BASE) +#define DMA2 ((DMA_Module*)NS_DMA2_BASE) +#define DMA1_CH1 ((DMA_ChannelType*)DMA1_CH1_BASE) +#define DMA1_CH2 ((DMA_ChannelType*)DMA1_CH2_BASE) +#define DMA1_CH3 ((DMA_ChannelType*)DMA1_CH3_BASE) +#define DMA1_CH4 ((DMA_ChannelType*)DMA1_CH4_BASE) +#define DMA1_CH5 ((DMA_ChannelType*)DMA1_CH5_BASE) +#define DMA1_CH6 ((DMA_ChannelType*)DMA1_CH6_BASE) +#define DMA1_CH7 ((DMA_ChannelType*)DMA1_CH7_BASE) +#define DMA1_CH8 ((DMA_ChannelType*)DMA1_CH8_BASE) +#define DMA2_CH1 ((DMA_ChannelType*)DMA2_CH1_BASE) +#define DMA2_CH2 ((DMA_ChannelType*)DMA2_CH2_BASE) +#define DMA2_CH3 ((DMA_ChannelType*)DMA2_CH3_BASE) +#define DMA2_CH4 ((DMA_ChannelType*)DMA2_CH4_BASE) +#define DMA2_CH5 ((DMA_ChannelType*)DMA2_CH5_BASE) +#define DMA2_CH6 ((DMA_ChannelType*)DMA2_CH6_BASE) +#define DMA2_CH7 ((DMA_ChannelType*)DMA2_CH7_BASE) +#define DMA2_CH8 ((DMA_ChannelType*)DMA2_CH8_BASE) + +/******************************************************************************/ +/* */ +/* DMA Controller */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for DMA_INTSTS register ********************/ +#define DMA_INTSTS_GLBF1 ((uint32_t)0x00000001) //!< Channel 1 Global interrupt flag +#define DMA_INTSTS_TXCF1 ((uint32_t)0x00000002) //!< Channel 1 Transfer Complete flag +#define DMA_INTSTS_HTXF1 ((uint32_t)0x00000004) //!< Channel 1 Half Transfer flag +#define DMA_INTSTS_ERRF1 ((uint32_t)0x00000008) //!< Channel 1 Transfer Error flag +#define DMA_INTSTS_GLBF2 ((uint32_t)0x00000010) //!< Channel 2 Global interrupt flag +#define DMA_INTSTS_TXCF2 ((uint32_t)0x00000020) //!< Channel 2 Transfer Complete flag +#define DMA_INTSTS_HTXF2 ((uint32_t)0x00000040) //!< Channel 2 Half Transfer flag +#define DMA_INTSTS_ERRF2 ((uint32_t)0x00000080) //!< Channel 2 Transfer Error flag +#define DMA_INTSTS_GLBF3 ((uint32_t)0x00000100) //!< Channel 3 Global interrupt flag +#define DMA_INTSTS_TXCF3 ((uint32_t)0x00000200) //!< Channel 3 Transfer Complete flag +#define DMA_INTSTS_HTXF3 ((uint32_t)0x00000400) //!< Channel 3 Half Transfer flag +#define DMA_INTSTS_ERRF3 ((uint32_t)0x00000800) //!< Channel 3 Transfer Error flag +#define DMA_INTSTS_GLBF4 ((uint32_t)0x00001000) //!< Channel 4 Global interrupt flag +#define DMA_INTSTS_TXCF4 ((uint32_t)0x00002000) //!< Channel 4 Transfer Complete flag +#define DMA_INTSTS_HTXF4 ((uint32_t)0x00004000) //!< Channel 4 Half Transfer flag +#define DMA_INTSTS_ERRF4 ((uint32_t)0x00008000) //!< Channel 4 Transfer Error flag +#define DMA_INTSTS_GLBF5 ((uint32_t)0x00010000) //!< Channel 5 Global interrupt flag +#define DMA_INTSTS_TXCF5 ((uint32_t)0x00020000) //!< Channel 5 Transfer Complete flag +#define DMA_INTSTS_HTXF5 ((uint32_t)0x00040000) //!< Channel 5 Half Transfer flag +#define DMA_INTSTS_ERRF5 ((uint32_t)0x00080000) //!< Channel 5 Transfer Error flag +#define DMA_INTSTS_GLBF6 ((uint32_t)0x00100000) //!< Channel 6 Global interrupt flag +#define DMA_INTSTS_TXCF6 ((uint32_t)0x00200000) //!< Channel 6 Transfer Complete flag +#define DMA_INTSTS_HTXF6 ((uint32_t)0x00400000) //!< Channel 6 Half Transfer flag +#define DMA_INTSTS_ERRF6 ((uint32_t)0x00800000) //!< Channel 6 Transfer Error flag +#define DMA_INTSTS_GLBF7 ((uint32_t)0x01000000) //!< Channel 7 Global interrupt flag +#define DMA_INTSTS_TXCF7 ((uint32_t)0x02000000) //!< Channel 7 Transfer Complete flag +#define DMA_INTSTS_HTXF7 ((uint32_t)0x04000000) //!< Channel 7 Half Transfer flag +#define DMA_INTSTS_ERRF7 ((uint32_t)0x08000000) //!< Channel 7 Transfer Error flag +#define DMA_INTSTS_GLBF8 ((uint32_t)0x10000000) //!< Channel 7 Global interrupt flag +#define DMA_INTSTS_TXCF8 ((uint32_t)0x20000000) //!< Channel 7 Transfer Complete flag +#define DMA_INTSTS_HTXF8 ((uint32_t)0x40000000) //!< Channel 7 Half Transfer flag +#define DMA_INTSTS_ERRF8 ((uint32_t)0x80000000) //!< Channel 7 Transfer Error flag + +/******************* Bit definition for DMA_INTCLR register *******************/ +#define DMA_INTCLR_CGLBF1 ((uint32_t)0x00000001) //!< Channel 1 Global interrupt clear +#define DMA_INTCLR_CTXCF1 ((uint32_t)0x00000002) //!< Channel 1 Transfer Complete clear +#define DMA_INTCLR_CHTXF1 ((uint32_t)0x00000004) //!< Channel 1 Half Transfer clear +#define DMA_INTCLR_CERRF1 ((uint32_t)0x00000008) //!< Channel 1 Transfer Error clear +#define DMA_INTCLR_CGLBF2 ((uint32_t)0x00000010) //!< Channel 2 Global interrupt clear +#define DMA_INTCLR_CTXCF2 ((uint32_t)0x00000020) //!< Channel 2 Transfer Complete clear +#define DMA_INTCLR_CHTXF2 ((uint32_t)0x00000040) //!< Channel 2 Half Transfer clear +#define DMA_INTCLR_CERRF2 ((uint32_t)0x00000080) //!< Channel 2 Transfer Error clear +#define DMA_INTCLR_CGLBF3 ((uint32_t)0x00000100) //!< Channel 3 Global interrupt clear +#define DMA_INTCLR_CTXCF3 ((uint32_t)0x00000200) //!< Channel 3 Transfer Complete clear +#define DMA_INTCLR_CHTXF3 ((uint32_t)0x00000400) //!< Channel 3 Half Transfer clear +#define DMA_INTCLR_CERRF3 ((uint32_t)0x00000800) //!< Channel 3 Transfer Error clear +#define DMA_INTCLR_CGLBF4 ((uint32_t)0x00001000) //!< Channel 4 Global interrupt clear +#define DMA_INTCLR_CTXCF4 ((uint32_t)0x00002000) //!< Channel 4 Transfer Complete clear +#define DMA_INTCLR_CHTXF4 ((uint32_t)0x00004000) //!< Channel 4 Half Transfer clear +#define DMA_INTCLR_CERRF4 ((uint32_t)0x00008000) //!< Channel 4 Transfer Error clear +#define DMA_INTCLR_CGLBF5 ((uint32_t)0x00010000) //!< Channel 5 Global interrupt clear +#define DMA_INTCLR_CTXCF5 ((uint32_t)0x00020000) //!< Channel 5 Transfer Complete clear +#define DMA_INTCLR_CHTXF5 ((uint32_t)0x00040000) //!< Channel 5 Half Transfer clear +#define DMA_INTCLR_CERRF5 ((uint32_t)0x00080000) //!< Channel 5 Transfer Error clear +#define DMA_INTCLR_CGLBF6 ((uint32_t)0x00100000) //!< Channel 6 Global interrupt clear +#define DMA_INTCLR_CTXCF6 ((uint32_t)0x00200000) //!< Channel 6 Transfer Complete clear +#define DMA_INTCLR_CHTXF6 ((uint32_t)0x00400000) //!< Channel 6 Half Transfer clear +#define DMA_INTCLR_CERRF6 ((uint32_t)0x00800000) //!< Channel 6 Transfer Error clear +#define DMA_INTCLR_CGLBF7 ((uint32_t)0x01000000) //!< Channel 7 Global interrupt clear +#define DMA_INTCLR_CTXCF7 ((uint32_t)0x02000000) //!< Channel 7 Transfer Complete clear +#define DMA_INTCLR_CHTXF7 ((uint32_t)0x04000000) //!< Channel 7 Half Transfer clear +#define DMA_INTCLR_CERRF7 ((uint32_t)0x08000000) //!< Channel 7 Transfer Error clear +#define DMA_INTCLR_CGLBF8 ((uint32_t)0x10000000) //!< Channel 7 Global interrupt clear +#define DMA_INTCLR_CTXCF8 ((uint32_t)0x20000000) //!< Channel 7 Transfer Complete clear +#define DMA_INTCLR_CHTXF8 ((uint32_t)0x40000000) //!< Channel 7 Half Transfer clear +#define DMA_INTCLR_CERRF8 ((uint32_t)0x80000000) //!< Channel 7 Transfer Error clear + +/******************* Bit definition for DMA_CHCFG1 register *******************/ +#define DMA_CHCFG1_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG1_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG1_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG1_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG1_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG1_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG1_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG1_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG1_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG1_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG1_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG1_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG1_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG1_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG1_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits(Channel Priority level) +#define DMA_CHCFG1_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG1_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG1_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/******************* Bit definition for DMA_CHCFG2 register *******************/ +#define DMA_CHCFG2_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG2_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG2_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG2_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG2_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG2_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG2_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG2_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG2_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG2_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG2_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG2_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG2_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG2_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG2_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG2_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG2_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG2_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/******************* Bit definition for DMA_CHCFG3 register *******************/ +#define DMA_CHCFG3_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG3_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG3_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG3_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG3_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG3_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG3_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG3_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG3_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG3_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG3_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG3_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG3_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG3_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG3_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG3_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG3_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG3_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/*!<****************** Bit definition for DMA_CHCFG4 register *******************/ +#define DMA_CHCFG4_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG4_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG4_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG4_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG4_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG4_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG4_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG4_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG4_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG4_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG4_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG4_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG4_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG4_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG4_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG4_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG4_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG4_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/****************** Bit definition for DMA_CHCFG5 register *******************/ +#define DMA_CHCFG5_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG5_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG5_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG5_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG5_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG5_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG5_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG5_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG5_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG5_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG5_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG5_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG5_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG5_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG5_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG5_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG5_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG5_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode enable + +/******************* Bit definition for DMA_CHCFG6 register *******************/ +#define DMA_CHCFG6_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG6_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG6_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG6_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG6_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG6_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG6_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG6_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG6_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG6_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG6_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG6_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG6_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG6_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG6_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG6_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG6_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG6_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/******************* Bit definition for DMA_CHCFG7 register *******************/ +#define DMA_CHCFG7_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG7_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG7_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG7_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG7_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG7_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG7_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG7_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG7_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG7_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG7_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG7_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG7_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG7_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG7_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG7_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG7_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG7_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode enable + +/******************* Bit definition for DMA_CHCFG8 register *******************/ +#define DMA_CHCFG8_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG8_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG8_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG8_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG8_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG8_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG8_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG8_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG8_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG8_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG8_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG8_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG8_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG8_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG8_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG8_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG8_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG8_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode enable + +/****************** Bit definition for DMA_TXNUM1 register ******************/ +#define DMA_TXNUM1_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM2 register ******************/ +#define DMA_TXNUM2_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM3 register ******************/ +#define DMA_TXNUM3_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM4 register ******************/ +#define DMA_TXNUM4_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM5 register ******************/ +#define DMA_TXNUM5_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM6 register ******************/ +#define DMA_TXNUM6_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM7 register ******************/ +#define DMA_TXNUM7_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM8 register ******************/ +#define DMA_TXNUM8_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_PADDR1 register *******************/ +#define DMA_PADDR1_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR2 register *******************/ +#define DMA_PADDR2_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR3 register *******************/ +#define DMA_PADDR3_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR4 register *******************/ +#define DMA_PADDR4_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR5 register *******************/ +#define DMA_PADDR5_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR6 register *******************/ +#define DMA_PADDR6_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR7 register *******************/ +#define DMA_PADDR7_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR8 register *******************/ +#define DMA_PADDR8_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_MADDR1 register *******************/ +#define DMA_MADDR1_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR2 register *******************/ +#define DMA_MADDR2_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR3 register *******************/ +#define DMA_MADDR3_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR4 register *******************/ +#define DMA_MADDR4_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR5 register *******************/ +#define DMA_MADDR5_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR6 register *******************/ +#define DMA_MADDR6_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR7 register *******************/ +#define DMA_MADDR7_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR8 register *******************/ +#define DMA_MADDR8_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_CHSEL1 register *******************/ +#define DMA_CHSEL1_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL2 register *******************/ +#define DMA_CHSEL2_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL3 register *******************/ +#define DMA_CHSEL3_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL4 register *******************/ +#define DMA_CHSEL4_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL5 register *******************/ +#define DMA_CHSEL5_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL6 register *******************/ +#define DMA_CHSEL6_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL7 register *******************/ +#define DMA_CHSEL7_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL8 register *******************/ +#define DMA_CHSEL8_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHMAPEN register *******************/ +#define DMA_CHMAPEN_MAP_EN ((uint32_t)0x00000001) //!< Channel Map Enable + +/* DMA1 Channelx interrupt pending bit masks */ +#define DMA1_CH1_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF1 | DMA_INTSTS_TXCF1 | DMA_INTSTS_HTXF1 | DMA_INTSTS_ERRF1)) +#define DMA1_CH2_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF2 | DMA_INTSTS_TXCF2 | DMA_INTSTS_HTXF2 | DMA_INTSTS_ERRF2)) +#define DMA1_CH3_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF3 | DMA_INTSTS_TXCF3 | DMA_INTSTS_HTXF3 | DMA_INTSTS_ERRF3)) +#define DMA1_CH4_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF4 | DMA_INTSTS_TXCF4 | DMA_INTSTS_HTXF4 | DMA_INTSTS_ERRF4)) +#define DMA1_CH5_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF5 | DMA_INTSTS_TXCF5 | DMA_INTSTS_HTXF5 | DMA_INTSTS_ERRF5)) +#define DMA1_CH6_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF6 | DMA_INTSTS_TXCF6 | DMA_INTSTS_HTXF6 | DMA_INTSTS_ERRF6)) +#define DMA1_CH7_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF7 | DMA_INTSTS_TXCF7 | DMA_INTSTS_HTXF7 | DMA_INTSTS_ERRF7)) +#define DMA1_CH8_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF8 | DMA_INTSTS_TXCF8 | DMA_INTSTS_HTXF8 | DMA_INTSTS_ERRF8)) + +/* DMA2 Channelx interrupt pending bit masks */ +#define DMA2_CH1_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF1 | DMA_INTSTS_TXCF1 | DMA_INTSTS_HTXF1 | DMA_INTSTS_ERRF1)) +#define DMA2_CH2_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF2 | DMA_INTSTS_TXCF2 | DMA_INTSTS_HTXF2 | DMA_INTSTS_ERRF2)) +#define DMA2_CH3_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF3 | DMA_INTSTS_TXCF3 | DMA_INTSTS_HTXF3 | DMA_INTSTS_ERRF3)) +#define DMA2_CH4_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF4 | DMA_INTSTS_TXCF4 | DMA_INTSTS_HTXF4 | DMA_INTSTS_ERRF4)) +#define DMA2_CH5_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF5 | DMA_INTSTS_TXCF5 | DMA_INTSTS_HTXF5 | DMA_INTSTS_ERRF5)) +#define DMA2_CH6_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF6 | DMA_INTSTS_TXCF6 | DMA_INTSTS_HTXF6 | DMA_INTSTS_ERRF6)) +#define DMA2_CH7_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF7 | DMA_INTSTS_TXCF7 | DMA_INTSTS_HTXF7 | DMA_INTSTS_ERRF7)) +#define DMA2_CH8_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF8 | DMA_INTSTS_TXCF8 | DMA_INTSTS_HTXF8 | DMA_INTSTS_ERRF8)) + +typedef struct { + __IO uint32_t INTSTS; + __IO uint32_t INTCLR; + __IO DMA_ChannelType DMA_Channel[8]; + __IO uint32_t CHMAPEN; +} DMA_Module; + +#define RCC_AHB_PERIPH_ADC1 ((uint32_t)0x00001000) +#define RCC_AHB_PERIPH_ADC2 ((uint32_t)0x00002000) +#define RCC_AHB_PERIPH_ADC3 ((uint32_t)0x00004000) +#define RCC_AHB_PERIPH_ADC4 ((uint32_t)0x00008000) + +void ADC_Init(ADC_Module* NS_ADCx, ADC_InitType* ADC_InitStruct); + +/**================================================================ + * ADC reset + ================================================================*/ +void ADC_DeInit(ADC_Module* NS_ADCx); + +/**================================================================ + * ADC module enable + ================================================================*/ +void ADC_Enable(ADC_Module* NS_ADCx, uint32_t Cmd); + +/**================================================================ + * Get the ADC status logo bit + ================================================================*/ +uint32_t ADC_GetFlagStatusNew(ADC_Module* NS_ADCx, uint8_t ADC_FLAG_NEW); + +/**================================================================ + * Open ADC calibration + ================================================================*/ +void ADC_StartCalibration(ADC_Module* NS_ADCx); + +/**================================================================ + * Enable ADC DMA + ================================================================*/ +void ADC_EnableDMA(ADC_Module* NS_ADCx, uint32_t Cmd); + +/**================================================================ + * Configure ADC interrupt enable + ================================================================*/ +void ADC_ConfigInt(ADC_Module* NS_ADCx, uint16_t ADC_IT, uint32_t Cmd); + +/**================================================================ + * Get ADC calibration status + ================================================================*/ +uint32_t ADC_GetCalibrationStatus(ADC_Module* NS_ADCx); + +/**================================================================ + * Configure the ADC channel + ================================================================*/ +void ADC_ConfigRegularChannel(ADC_Module* NS_ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); + +/**================================================================ + * Start ADC conversion + ================================================================*/ +void ADC_EnableSoftwareStartConv(ADC_Module* NS_ADCx, uint32_t Cmd); + +/**================================================================ + * Get the ADC status logo bit + ================================================================*/ +uint32_t ADC_GetFlagStatus(ADC_Module* NS_ADCx, uint8_t ADC_FLAG); + +/**================================================================ + * Clear status logo bit + ================================================================*/ +void ADC_ClearFlag(ADC_Module* NS_ADCx, uint8_t ADC_FLAG); + +/**================================================================ + * Get ADC sampling value + ================================================================*/ +uint16_t ADC_GetDat(ADC_Module* NS_ADCx); + +//////////////////////////////////////////////////////////////////////////////// + +typedef struct { + __IO uint32_t CR; /* Completely compatible */ + __IO uint32_t CFGR; /* Not compatible: ADC frequency is not set here */ + __IO uint32_t CIR; /* Completely compatible */ + + __IO uint32_t APB2RSTR; /* Completely compatible */ + __IO uint32_t APB1RSTR; /* Completely compatible */ + + __IO uint32_t AHBENR; /* Not compatible: ADC clock enables settings here */ + __IO uint32_t APB2ENR; /* Not compatible: ADC clock enables to be here */ + __IO uint32_t APB1ENR; /* compatible */ + __IO uint32_t BDCR; /* compatible */ + __IO uint32_t CSR; /* compatible */ + + __IO uint32_t AHBRSTR; /* Not compatible, ADC reset here settings */ + __IO uint32_t CFGR2; /* Not compatible, ADC clock settings here */ + __IO uint32_t CFGR3; /* Not compatible, add a new register */ + +} RCC_TypeDef; + +#define RCC ((RCC_TypeDef *) ADC_RCC_BASE) + +/**================================================================ + * Initialize ADC clock + ================================================================*/ + +void enable_adc_clk(uint8_t cmd); + +/**================================================================ + * Initialize ADC peripheral parameters + ================================================================*/ +void ADC_Initial(ADC_Module* NS_ADCx); + +/**================================================================ + * Single independent sampling + ================================================================*/ +uint16_t ADC_GetData(ADC_Module* NS_ADCx, uint8_t ADC_Channel); + +void DMA_DeInit(DMA_ChannelType* DMAyChx); + +#define CCR_CLEAR_Mask ((uint32_t)0xFFFF800F) + +void DMA_Init(DMA_ChannelType* DMAyChx, DMA_InitType* DMA_InitParam); + +void DMA_EnableChannel(DMA_ChannelType* DMAyChx, uint32_t Cmd); + +#define USE_ADC NS_ADC2 +#define USE_DMA_CH DMA1_CH8 + +/**================================================================ + * Initialize the DMA of ADC + ================================================================*/ +void ADC_DMA_init(); diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp index abb348d743..b5b57536f3 100644 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp index 6dabcde51e..3b26b630df 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp @@ -28,7 +28,7 @@ // Copied from ~/.platformio/packages/framework-arduinoststm32-maple/STM32F1/system/libmaple/usart_private.h // Changed to handle Emergency Parser -static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) { +FORCE_INLINE void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) { /* Handle RXNEIE and TXEIE interrupts. * RXNE signifies availability of a byte in DR. * @@ -75,9 +75,9 @@ static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb } // Not every MarlinSerial port should handle emergency parsing. -// It would not make sense to parse GCode from TMC responses, for example. +// It would not make sense to parse G-Code from TMC responses, for example. constexpr bool serial_handles_emergency(int port) { - return false + return (false #ifdef SERIAL_PORT || (SERIAL_PORT) == port #endif @@ -87,7 +87,7 @@ constexpr bool serial_handles_emergency(int port) { #ifdef LCD_SERIAL_PORT || (LCD_SERIAL_PORT) == port #endif - ; + ); } #define DEFINE_HWSERIAL_MARLIN(name, n) \ @@ -116,7 +116,7 @@ constexpr bool serial_handles_emergency(int port) { #endif DEFINE_HWSERIAL_MARLIN(MSerial2, 2); DEFINE_HWSERIAL_MARLIN(MSerial3, 3); -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) DEFINE_HWSERIAL_UART_MARLIN(MSerial4, 4); DEFINE_HWSERIAL_UART_MARLIN(MSerial5, 5); #endif diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.h b/Marlin/src/HAL/STM32F1/MarlinSerial.h index dda32fe7a2..c2dc5bd571 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.h +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.h @@ -28,6 +28,29 @@ #include "../../inc/MarlinConfigPre.h" #include "../../core/serial_hook.h" +#ifdef SERIAL_USB + typedef ForwardSerial1Class< USBSerial > DefaultSerial1; + extern DefaultSerial1 MSerial0; + #if HAS_SD_HOST_DRIVE + #define UsbSerial MarlinCompositeSerial + #else + #define UsbSerial MSerial0 + #endif +#endif + +#define SERIAL_INDEX_MIN 1 +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) + #define SERIAL_INDEX_MAX 5 +#else + #define SERIAL_INDEX_MAX 3 +#endif +#define USB_SERIAL_PORT(...) UsbSerial +#include "../shared/serial_ports.h" + +#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() +#endif + // Increase priority of serial interrupts, to reduce overflow errors #define UART_IRQ_PRIO 1 @@ -52,7 +75,7 @@ typedef Serial1Class MSerialT; extern MSerialT MSerial1; extern MSerialT MSerial2; extern MSerialT MSerial3; -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) extern MSerialT MSerial4; extern MSerialT MSerial5; #endif diff --git a/Marlin/src/HAL/STM32F1/MinSerial.cpp b/Marlin/src/HAL/STM32F1/MinSerial.cpp index 6cf68d8d8f..0d9a611d7e 100644 --- a/Marlin/src/HAL/STM32F1/MinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MinSerial.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -93,7 +92,7 @@ void install_min_serial() { HAL_min_serial_out = &TX; } -#if DISABLED(DYNAMIC_VECTORTABLE) && DISABLED(STM32F0xx) // Cortex M0 can't branch to a symbol that's too far, so we have a specific hack for them +#if NONE(DYNAMIC_VECTORTABLE, STM32F0xx) // Cortex M0 can't branch to a symbol that's too far, so we have a specific hack for them extern "C" { __attribute__((naked)) void JumpHandler_ASM() { __asm__ __volatile__ ( diff --git a/Marlin/src/HAL/STM32F1/README.md b/Marlin/src/HAL/STM32F1/README.md index b5bd5141fb..e289f35433 100644 --- a/Marlin/src/HAL/STM32F1/README.md +++ b/Marlin/src/HAL/STM32F1/README.md @@ -5,6 +5,7 @@ This HAL is for STM32F103 boards used with [Arduino STM32](https://github.com/ro Currently has been tested in Malyan M200 (103CBT6), SKRmini (103RCT6), Chitu 3d (103ZET6), and various 103VET6 boards. ### Main developers: + - Victorpv - xC000005 - thisiskeithb diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index 1ce2c7d3fd..ab111ddbf0 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -517,7 +517,6 @@ uint8_t SPIClass::dmaSendAsync(const void * transmitBuf, uint16_t length, bool m return b; } - /** * New functions added to manage callbacks. * Victor Perez 2017 @@ -526,23 +525,22 @@ void SPIClass::onReceive(void(*callback)()) { _currentSetting->receiveCallback = callback; if (callback) { switch (_currentSetting->spi_d->clk_id) { - #if BOARD_NR_SPI >= 1 - case RCC_SPI1: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi1EventCallback); - break; - #endif - #if BOARD_NR_SPI >= 2 - case RCC_SPI2: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi2EventCallback); - break; - #endif - #if BOARD_NR_SPI >= 3 - case RCC_SPI3: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi3EventCallback); - break; - #endif - default: - ASSERT(0); + #if BOARD_NR_SPI >= 1 + case RCC_SPI1: + dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi1EventCallback); + break; + #endif + #if BOARD_NR_SPI >= 2 + case RCC_SPI2: + dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi2EventCallback); + break; + #endif + #if BOARD_NR_SPI >= 3 + case RCC_SPI3: + dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi3EventCallback); + break; + #endif + default: ASSERT(0); } } else { @@ -554,23 +552,22 @@ void SPIClass::onTransmit(void(*callback)()) { _currentSetting->transmitCallback = callback; if (callback) { switch (_currentSetting->spi_d->clk_id) { - #if BOARD_NR_SPI >= 1 - case RCC_SPI1: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi1EventCallback); - break; - #endif - #if BOARD_NR_SPI >= 2 - case RCC_SPI2: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi2EventCallback); - break; - #endif - #if BOARD_NR_SPI >= 3 - case RCC_SPI3: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi3EventCallback); - break; - #endif - default: - ASSERT(0); + #if BOARD_NR_SPI >= 1 + case RCC_SPI1: + dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi1EventCallback); + break; + #endif + #if BOARD_NR_SPI >= 2 + case RCC_SPI2: + dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi2EventCallback); + break; + #endif + #if BOARD_NR_SPI >= 3 + case RCC_SPI3: + dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi3EventCallback); + break; + #endif + default: ASSERT(0); } } else { diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h index 13f4d5ed6c..72063df699 100644 --- a/Marlin/src/HAL/STM32F1/SPI.h +++ b/Marlin/src/HAL/STM32F1/SPI.h @@ -33,6 +33,17 @@ #include #include +#include "../../core/macros.h" // for PIN_EXISTS + +// Number of SPI ports +#if PIN_EXISTS(BOARD_SPI3_SCK) + #define BOARD_NR_SPI 3 +#elif PIN_EXISTS(BOARD_SPI2_SCK) + #define BOARD_NR_SPI 2 +#elif PIN_EXISTS(BOARD_SPI1_SCK) + #define BOARD_NR_SPI 1 +#endif + // SPI_HAS_TRANSACTION means SPI has // - beginTransaction() // - endTransaction() @@ -49,7 +60,7 @@ #define SPI_CLOCK_DIV128 SPI_BAUD_PCLK_DIV_128 #define SPI_CLOCK_DIV256 SPI_BAUD_PCLK_DIV_256 -/* +/** * Roger Clark. 20150106 * Commented out redundant AVR defined * @@ -144,7 +155,7 @@ private: friend class SPIClass; }; -/* +/** * Kept for compat. */ static const uint8_t ff = 0xFF; @@ -224,7 +235,7 @@ public: void onReceive(void(*)()); void onTransmit(void(*)()); - /* + /** * I/O */ @@ -305,7 +316,7 @@ public: uint8_t dmaSendRepeat(uint16_t length); uint8_t dmaSendAsync(const void * transmitBuf, uint16_t length, bool minc = 1); - /* + /** * Pin accessors */ @@ -389,7 +400,7 @@ private: void updateSettings(); - /* + /** * Functions added for DMA transfers with Callback. * Experimental. */ diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index 47ffb631cf..00caec287b 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -30,8 +29,6 @@ uint8_t ServoCount = 0; #include "Servo.h" -//#include "Servo.h" - #include #include #include diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index 745a1c93f0..ffafc23833 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32F1/adc.h b/Marlin/src/HAL/STM32F1/adc.h new file mode 100644 index 0000000000..a2f5652de0 --- /dev/null +++ b/Marlin/src/HAL/STM32F1/adc.h @@ -0,0 +1,58 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) + * + * adc.h - Define enumerated indices for enabled ADC Features + */ + +#include "../../inc/MarlinConfig.h" + +enum ADCIndex : uint8_t { + OPTITEM(HAS_TEMP_ADC_0, TEMP_0 ) + OPTITEM(HAS_TEMP_ADC_1, TEMP_1 ) + OPTITEM(HAS_TEMP_ADC_2, TEMP_2 ) + OPTITEM(HAS_TEMP_ADC_3, TEMP_3 ) + OPTITEM(HAS_TEMP_ADC_4, TEMP_4 ) + OPTITEM(HAS_TEMP_ADC_5, TEMP_5 ) + OPTITEM(HAS_TEMP_ADC_6, TEMP_6 ) + OPTITEM(HAS_TEMP_ADC_7, TEMP_7 ) + OPTITEM(HAS_TEMP_ADC_BED, TEMP_BED ) + OPTITEM(HAS_TEMP_ADC_CHAMBER, TEMP_CHAMBER ) + OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE ) + OPTITEM(HAS_TEMP_ADC_COOLER, TEMP_COOLER ) + OPTITEM(HAS_TEMP_ADC_BOARD, TEMP_BOARD ) + OPTITEM(HAS_TEMP_ADC_SOC, TEMP_SOC ) + OPTITEM(HAS_FILWIDTH_ADC, FILWIDTH ) + OPTITEM(HAS_FILWIDTH2_ADC, FILWIDTH2 ) + OPTITEM(HAS_ADC_BUTTONS, ADC_KEY ) + OPTITEM(HAS_JOY_ADC_X, JOY_X ) + OPTITEM(HAS_JOY_ADC_Y, JOY_Y ) + OPTITEM(HAS_JOY_ADC_Z, JOY_Z ) + OPTITEM(POWER_MONITOR_CURRENT, POWERMON_CURRENT ) + OPTITEM(POWER_MONITOR_VOLTAGE, POWERMON_VOLTAGE ) + ADC_COUNT +}; + +extern uint16_t adc_results[ADC_COUNT]; diff --git a/Marlin/src/HAL/STM32F1/build_flags.py b/Marlin/src/HAL/STM32F1/build_flags.py deleted file mode 100755 index 970ca8b767..0000000000 --- a/Marlin/src/HAL/STM32F1/build_flags.py +++ /dev/null @@ -1,56 +0,0 @@ -from __future__ import print_function -import sys - -#dynamic build flags for generic compile options -if __name__ == "__main__": - args = " ".join([ "-std=gnu++14", - "-Os", - "-mcpu=cortex-m3", - "-mthumb", - - "-fsigned-char", - "-fno-move-loop-invariants", - "-fno-strict-aliasing", - "-fsingle-precision-constant", - - "--specs=nano.specs", - "--specs=nosys.specs", - - "-IMarlin/src/HAL/STM32F1", - - "-MMD", - "-MP", - "-DTARGET_STM32F1" - ]) - - for i in range(1, len(sys.argv)): - args += " " + sys.argv[i] - - print(args) - -# extra script for linker options -else: - import pioutil - if pioutil.is_pio_build(): - from SCons.Script import DefaultEnvironment - env = DefaultEnvironment() - env.Append( - ARFLAGS=["rcs"], - - ASFLAGS=["-x", "assembler-with-cpp"], - - CXXFLAGS=[ - "-fabi-version=0", - "-fno-use-cxa-atexit", - "-fno-threadsafe-statics" - ], - LINKFLAGS=[ - "-Os", - "-mcpu=cortex-m3", - "-ffreestanding", - "-mthumb", - "--specs=nano.specs", - "--specs=nosys.specs", - "-u_printf_float", - ], - ) diff --git a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32F1/eeprom/eeprom_bl24cxx.cpp similarity index 89% rename from Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp rename to Marlin/src/HAL/STM32F1/eeprom/eeprom_bl24cxx.cpp index 4e25bc69da..9e96a741bf 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom/eeprom_bl24cxx.cpp @@ -26,12 +26,12 @@ * with simple implementations supplied by Marlin. */ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(IIC_BL24CXX_EEPROM) -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" // // PersistentStore @@ -41,7 +41,7 @@ #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM." #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { eeprom_init(); return true; } bool PersistentStore::access_finish() { return true; } @@ -50,7 +50,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui uint16_t written = 0; while (size--) { uint8_t v = *value; - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes @@ -68,8 +68,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t * const p = (uint8_t * const)pos; - uint8_t c = eeprom_read_byte(p); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom/eeprom_flash.cpp similarity index 79% rename from Marlin/src/HAL/STM32F1/eeprom_flash.cpp rename to Marlin/src/HAL/STM32F1/eeprom/eeprom_flash.cpp index e7d9dd29e2..2292c02203 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -29,33 +28,33 @@ #ifdef __STM32F1__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(FLASH_EEPROM_EMULATION) -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_api.h" #include #include // Store settings in the last two pages #ifndef MARLIN_EEPROM_SIZE - #define MARLIN_EEPROM_SIZE ((EEPROM_PAGE_SIZE) * 2) + #define MARLIN_EEPROM_SIZE ((EEPROM_PAGE_SIZE) * 2UL) #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static bool eeprom_dirty = false; bool PersistentStore::access_start() { - const uint32_t *source = reinterpret_cast(EEPROM_PAGE0_BASE); - uint32_t *destination = reinterpret_cast(ram_eeprom); + const uint32_t *src = reinterpret_cast(EEPROM_PAGE0_BASE); + uint32_t *dst = reinterpret_cast(ram_eeprom); static_assert(0 == (MARLIN_EEPROM_SIZE) % 4, "MARLIN_EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe constexpr size_t eeprom_size_u32 = (MARLIN_EEPROM_SIZE) / 4; - for (size_t i = 0; i < eeprom_size_u32; ++i, ++destination, ++source) - *destination = *source; + for (size_t i = 0; i < eeprom_size_u32; ++i, ++dst, ++src) + *dst = *src; eeprom_dirty = false; return true; @@ -81,9 +80,9 @@ bool PersistentStore::access_finish() { status = FLASH_ErasePage(EEPROM_PAGE1_BASE); if (status != FLASH_COMPLETE) ACCESS_FINISHED(true); - const uint16_t *source = reinterpret_cast(ram_eeprom); - for (size_t i = 0; i < MARLIN_EEPROM_SIZE; i += 2, ++source) { - if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *source) != FLASH_COMPLETE) + const uint16_t *src = reinterpret_cast(ram_eeprom); + for (size_t i = 0; i < long(MARLIN_EEPROM_SIZE); i += 2, ++src) { + if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *src) != FLASH_COMPLETE) ACCESS_FINISHED(false); } diff --git a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32F1/eeprom/eeprom_if_iic.cpp similarity index 90% rename from Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp rename to Marlin/src/HAL/STM32F1/eeprom/eeprom_if_iic.cpp index 78b7af0b04..e7e7fc1db1 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom/eeprom_if_iic.cpp @@ -27,12 +27,12 @@ #ifdef __STM32F1__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(IIC_BL24CXX_EEPROM) -#include "../../libs/BL24CXX.h" -#include "../shared/eeprom_if.h" +#include "../../../libs/BL24CXX.h" +#include "../../shared/eeprom_if.h" void eeprom_init() { BL24CXX::init(); } @@ -42,7 +42,7 @@ void eeprom_init() { BL24CXX::init(); } void eeprom_write_byte(uint8_t *pos, uint8_t value) { const unsigned eeprom_address = (unsigned)pos; - return BL24CXX::writeOneByte(eeprom_address, value); + BL24CXX::writeOneByte(eeprom_address, value); } uint8_t eeprom_read_byte(uint8_t *pos) { diff --git a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32F1/eeprom/eeprom_sdcard.cpp similarity index 88% rename from Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp rename to Marlin/src/HAL/STM32F1/eeprom/eeprom_sdcard.cpp index d608ccee14..e41c6e0aa0 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom/eeprom_sdcard.cpp @@ -27,19 +27,19 @@ #ifdef __STM32F1__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "../shared/eeprom_api.h" -#include "../../sd/cardreader.h" +#include "../../shared/eeprom_api.h" +#include "../../../sd/cardreader.h" #define EEPROM_FILENAME "eeprom.dat" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } #define _ALIGN(x) __attribute__ ((aligned(x))) // SDIO uint32_t* compat. static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE]; @@ -47,13 +47,13 @@ static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE]; bool PersistentStore::access_start() { if (!card.isMounted()) return false; - SdFile file, root = card.getroot(); + MediaFile file, root = card.getroot(); if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) return true; // false aborts the save int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE); if (bytes_read < 0) return false; - for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++) + for (; bytes_read < long(MARLIN_EEPROM_SIZE); bytes_read++) HAL_eeprom_data[bytes_read] = 0xFF; file.close(); return true; @@ -62,7 +62,7 @@ bool PersistentStore::access_start() { bool PersistentStore::access_finish() { if (!card.isMounted()) return false; - SdFile file, root = card.getroot(); + MediaFile file, root = card.getroot(); int bytes_written = 0; if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE); diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom/eeprom_wired.cpp similarity index 89% rename from Marlin/src/HAL/STM32F1/eeprom_wired.cpp rename to Marlin/src/HAL/STM32F1/eeprom/eeprom_wired.cpp index bc48eef34f..a1464ab983 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom/eeprom_wired.cpp @@ -26,17 +26,17 @@ #ifdef __STM32F1__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if USE_WIRED_EEPROM -#include "../shared/eeprom_if.h" -#include "../shared/eeprom_api.h" +#include "../../shared/eeprom_if.h" +#include "../../shared/eeprom_api.h" #ifndef MARLIN_EEPROM_SIZE #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_finish() { return true; } @@ -57,7 +57,7 @@ bool PersistentStore::access_start() { bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { uint16_t written = 0; while (size--) { - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); uint8_t v = *value; if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); @@ -76,7 +76,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t c = eeprom_read_byte((uint8_t*)pos); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing && value) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h index a1ef8a8c3a..f8f21a4c6d 100644 --- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -28,7 +27,7 @@ * On STM32F, all pins support external interrupt capability. * Any pin can be used for external interrupts, but there are some restrictions. * At most 16 different external interrupts can be used at one time. - * Further, you can’t just pick any 16 pins to use. This is because every pin on the STM32 + * Further, you can't just pick any 16 pins to use. This is because every pin on the STM32 * connects to what is called an EXTI line, and only one pin per EXTI line can be used for external interrupts at a time * Check the Reference Manual of the MCU to confirm which line is used by each pin */ @@ -54,33 +53,34 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); - TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 297804a3ac..c3f96f0f92 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -39,7 +39,7 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) { void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { const uint16_t duty = invert ? v_size - v : v; if (PWM_PIN(pin)) { - timer_dev *timer; UNUSED(timer); + timer_dev *timer; if (timer_freq[timer_and_index_for_pin(pin, &timer)] == 0) set_pwm_frequency(pin, PWM_FREQUENCY); const uint8_t channel = PIN_MAP[pin].timer_channel; @@ -55,7 +55,7 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - timer_dev *timer; UNUSED(timer); + timer_dev *timer; timer_freq[timer_and_index_for_pin(pin, &timer)] = f_desired; // Protect used timers diff --git a/Marlin/src/HAL/STM32F1/fastio.h b/Marlin/src/HAL/STM32F1/fastio.h index e75254d692..8bb986b466 100644 --- a/Marlin/src/HAL/STM32F1/fastio.h +++ b/Marlin/src/HAL/STM32F1/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -45,6 +44,7 @@ #define SET_INPUT_PULLUP(IO) _SET_MODE(IO, GPIO_INPUT_PU) #define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, GPIO_INPUT_PD) #define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) +#define SET_OUTPUT_OD(IO) OUT_WRITE_OD(IO, LOW) #define SET_PWM(IO) pinMode(IO, PWM) // do{ gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, GPIO_AF_OUTPUT_PP); timer_set_mode(PIN_MAP[pin].timer_device, PIN_MAP[pin].timer_channel, TIMER_PWM); }while(0) #define SET_PWM_OD(IO) pinMode(IO, PWM_OPEN_DRAIN) diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h index 656fbe1ce2..f130f5cad8 100644 --- a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h @@ -24,11 +24,11 @@ // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif -// Allow SDSUPPORT to be disabled -#if DISABLED(SDSUPPORT) - #undef SDIO_SUPPORT +// Allow for no media drives +#if !HAS_MEDIA + #undef ONBOARD_SDIO #endif diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_type.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index fe8f6e0ec2..1da42dcc8f 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -25,7 +25,7 @@ * Test STM32F1-specific configuration values for errors at compile-time. */ -#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT) +#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise #if USE_FALLBACK_EEPROM #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." diff --git a/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf b/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf index c39f4ce0ed..0df30d2c42 100644 --- a/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf +++ b/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf @@ -48,7 +48,6 @@ ServiceBinary=%12%\usbser.sys ; String Definitions ;------------------------------------------------------------------------------ - [Strings] STM = "LeafLabs" MFGNAME = "LeafLabs" diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index 7828479658..9191614587 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -22,11 +22,23 @@ #pragma once /** - * Support routines for MAPLE_STM32F1 - */ - -/** - * Translation of routines & variables used by pinsDebug.h + * Pins Debugging for Maple STM32F1 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) */ #ifndef BOARD_NR_GPIO_PINS // Only in MAPLE_STM32F1 @@ -39,14 +51,12 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]; #define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS #define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS -#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS) -#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin) -#define pwm_status(pin) PWM_PIN(pin) -#define digitalRead_mod(p) extDigitalRead(p) -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PORT(p) print_port(p) -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define isValidPin(P) (P >= 0 && P < BOARD_NR_GPIO_PINS) +#define getPinByIndex(x) pin_t(pin_array[x].pin) +#define digitalRead_mod(P) extDigitalRead(P) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(P)); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin // pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities @@ -54,21 +64,19 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]; #define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX) #endif -static int8_t get_pin_mode(pin_t pin) { - return VALID_PIN(pin) ? _GET_MODE(pin) : -1; -} +int8_t get_pin_mode(const pin_t pin) { return isValidPin(pin) ? _GET_MODE(pin) : -1; } -static pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { - if (!VALID_PIN(pin)) return -1; - int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel); +int8_t digitalPinToAnalogIndex(const pin_t pin) { + if (!isValidPin(pin)) return -1; + pin_t adc_channel = pin_t(PIN_MAP[pin].adc_channel); #ifdef NUM_ANALOG_INPUTS - if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx; + if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = (pin_t)ADCx; #endif - return pin_t(adc_channel); + return adc_channel; } -static bool IS_ANALOG(pin_t pin) { - if (!VALID_PIN(pin)) return false; +bool isAnalogPin(const pin_t pin) { + if (!isValidPin(pin)) return false; if (PIN_MAP[pin].adc_channel != ADCx) { #ifdef NUM_ANALOG_INPUTS if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false; @@ -78,13 +86,13 @@ static bool IS_ANALOG(pin_t pin) { return false; } -static bool GET_PINMODE(const pin_t pin) { - return VALID_PIN(pin) && !IS_INPUT(pin); +bool getValidPinMode(const pin_t pin) { + return isValidPin(pin) && !IS_INPUT(pin); } -static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { - const pin_t pin = GET_ARRAY_PIN(array_pin); - return (!IS_ANALOG(pin) +bool getPinIsDigitalByIndex(const int16_t index) { + const pin_t pin = getPinByIndex(index); + return (!isAnalogPin(pin) #ifdef NUM_ANALOG_INPUTS || PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS #endif @@ -93,12 +101,12 @@ static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { #include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density -static void pwm_details(const pin_t pin) { +void printPinPWM(const pin_t pin) { if (PWM_PIN(pin)) { timer_dev * const tdev = PIN_MAP[pin].timer_device; const uint8_t channel = PIN_MAP[pin].timer_channel; const char num = ( - #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) + #if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) tdev == &timer8 ? '8' : tdev == &timer5 ? '5' : #endif @@ -113,7 +121,9 @@ static void pwm_details(const pin_t pin) { } } -static void print_port(pin_t pin) { +bool pwm_status(const pin_t pin) { return PWM_PIN(pin); } + +void printPinPort(const pin_t pin) { const char port = 'A' + char(pin >> 4); // pin div 16 const int16_t gbit = PIN_MAP[pin].gpio_bit; char buffer[8]; diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/sd/msc_sd.cpp similarity index 86% rename from Marlin/src/HAL/STM32F1/msc_sd.cpp rename to Marlin/src/HAL/STM32F1/sd/msc_sd.cpp index f490c83ed8..5f1ba30c8a 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/sd/msc_sd.cpp @@ -1,34 +1,42 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ #ifdef __STM32F1__ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_SD_HOST_DRIVE #include "msc_sd.h" -#include "SPI.h" -#include "usb_reg_map.h" +#include "../SPI.h" + +#include #define PRODUCT_ID 0x29 USBMassStorage MarlinMSC; Serial1Class MarlinCompositeSerial(true); -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if SD_CONNECTION_IS(ONBOARD) diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/sd/msc_sd.h similarity index 64% rename from Marlin/src/HAL/STM32F1/msc_sd.h rename to Marlin/src/HAL/STM32F1/sd/msc_sd.h index f4636bdff7..871d98eaf2 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.h +++ b/Marlin/src/HAL/STM32F1/sd/msc_sd.h @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * * You should have received a copy of the GNU General Public License * along with this program. If not, see . * @@ -17,8 +24,8 @@ #include -#include "../../inc/MarlinConfigPre.h" -#include "../../core/serial_hook.h" +#include "../../../inc/MarlinConfigPre.h" +#include "../../../core/serial_hook.h" extern USBMassStorage MarlinMSC; extern Serial1Class MarlinCompositeSerial; diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/sd/onboard_sd.cpp similarity index 99% rename from Marlin/src/HAL/STM32F1/onboard_sd.cpp rename to Marlin/src/HAL/STM32F1/sd/onboard_sd.cpp index a3d8dcb2d5..ace1204b75 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/sd/onboard_sd.cpp @@ -13,13 +13,13 @@ #ifdef __STM32F1__ -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if SD_CONNECTION_IS(ONBOARD) #include "onboard_sd.h" -#include "SPI.h" -#include "fastio.h" +#include "../SPI.h" +#include "../fastio.h" #ifndef ONBOARD_SPI_DEVICE #define ONBOARD_SPI_DEVICE SPI_DEVICE diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.h b/Marlin/src/HAL/STM32F1/sd/onboard_sd.h similarity index 80% rename from Marlin/src/HAL/STM32F1/onboard_sd.h rename to Marlin/src/HAL/STM32F1/sd/onboard_sd.h index f228d068c9..be1d1d0a6b 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.h +++ b/Marlin/src/HAL/STM32F1/sd/onboard_sd.h @@ -1,11 +1,31 @@ -/*----------------------------------------------------------------------- -/ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] -/ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] -/ * Low level disk interface module include file (C)ChaN, 2015 -/-----------------------------------------------------------------------*/ - +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 +/*----------------------------------------------------------------------- +/ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] +/ * Low level disk interface module include file (c) ChaN, 2015 +/-----------------------------------------------------------------------*/ + #define _DISKIO_WRITE 1 /* 1: Enable disk_write function */ #define _DISKIO_IOCTL 1 /* 1: Enable disk_ioctl function */ #define _DISKIO_ISDIO 0 /* 1: Enable iSDIO control function */ @@ -27,7 +47,6 @@ typedef enum { RES_PARERR /* 4: Invalid Parameter */ } DRESULT; - #if _DISKIO_ISDIO /* Command structure for iSDIO ioctl command */ typedef struct { diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sd/sdio.cpp similarity index 96% rename from Marlin/src/HAL/STM32F1/sdio.cpp rename to Marlin/src/HAL/STM32F1/sd/sdio.cpp index 6e41d2cbf1..d657fd3b0e 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sd/sdio.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -20,13 +19,13 @@ * along with this program. If not, see . * */ -#ifdef ARDUINO_ARCH_STM32F1 +#ifdef __STM32F1__ #include -#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density +#include "../../../inc/MarlinConfig.h" // Allow pins/pins.h to set density -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) #include "sdio.h" @@ -136,12 +135,17 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) { } bool SDIO_ReadBlock(uint32_t blockAddress, uint8_t *data) { - uint32_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadBlock_DMA(blockAddress, data)) return true; + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) { + if (SDIO_ReadBlock_DMA(blockAddress, data)) return true; + #if SD_RETRY_DELAY_MS + delay(SD_RETRY_DELAY_MS); + #endif + } return false; } -uint32_t millis(); +unsigned long millis(); bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) { if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false; @@ -215,7 +219,7 @@ bool SDIO_CmdAppSetBusWidth(uint32_t rsa, uint32_t argument) { bool SDIO_CmdAppOperCommand(uint32_t sdType) { if (!SDIO_CmdAppCommand(0)) return false; - SDIO_SendCommand(ACMD41_SD_APP_OP_COND , SDMMC_VOLTAGE_WINDOW_SD | sdType); + SDIO_SendCommand(ACMD41_SD_APP_OP_COND, SDMMC_VOLTAGE_WINDOW_SD | sdType); return SDIO_GetCmdResp3(); } @@ -304,4 +308,4 @@ bool SDIO_GetCmdResp7() { } #endif // STM32_HIGH_DENSITY || STM32_XL_DENSITY -#endif // ARDUINO_ARCH_STM32F1 +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/sdio.h b/Marlin/src/HAL/STM32F1/sd/sdio.h similarity index 97% rename from Marlin/src/HAL/STM32F1/sdio.h rename to Marlin/src/HAL/STM32F1/sd/sdio.h index 8777299f01..ffcd354915 100644 --- a/Marlin/src/HAL/STM32F1/sdio.h +++ b/Marlin/src/HAL/STM32F1/sd/sdio.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -21,7 +21,7 @@ */ #pragma once -#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to override SDIO clock / retries +#include "../../../inc/MarlinConfig.h" // Allow pins/pins.h to override SDIO clock / retries #include #include @@ -60,7 +60,6 @@ #define ACMD41_SD_APP_OP_COND (uint16_t)(SDMMC_ACMD_SD_APP_OP_COND | SDIO_CMD_WAIT_SHORT_RESP) #define ACMD42_SD_APP_SET_CLR_CARD_DETECT (uint16_t)(SDMMC_ACMD_SD_APP_SET_CLR_CARD_DETECT | SDIO_CMD_WAIT_SHORT_RESP) - #define SDMMC_ALLZERO 0x00000000U #define SDMMC_OCR_ERRORBITS 0xFDFFE008U diff --git a/Marlin/src/HAL/STM32F1/spi_pins.h b/Marlin/src/HAL/STM32F1/spi_pins.h index 3d3c8f8d2f..d9c5e1f8c6 100644 --- a/Marlin/src/HAL/STM32F1/spi_pins.h +++ b/Marlin/src/HAL/STM32F1/spi_pins.h @@ -46,11 +46,6 @@ #ifndef SD_MOSI_PIN #define SD_MOSI_PIN PA7 #endif -#ifndef SD_SS_PIN - #define SD_SS_PIN PA4 -#endif -#undef SDSS -#define SDSS SD_SS_PIN #ifndef SPI_DEVICE #define SPI_DEVICE 1 diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp index 5b52fb416f..73b0e7efb9 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp @@ -20,6 +20,8 @@ * */ +#ifdef __STM32F1__ + #include "../../../inc/MarlinConfig.h" #if HAS_FSMC_TFT @@ -84,8 +86,7 @@ __attribute__((always_inline)) __STATIC_INLINE void __DSB() { #define FSMC_ADDRESS_SETUP_TIME 15 // AddressSetupTime #define FSMC_DATA_SETUP_TIME 15 // DataSetupTime -static uint8_t fsmcInit = 0; -void TFT_FSMC::Init() { +void TFT_FSMC::init() { uint8_t cs = FSMC_CS_PIN, rs = FSMC_RS_PIN; uint32_t controllerAddress; @@ -97,8 +98,9 @@ void TFT_FSMC::Init() { struct fsmc_nor_psram_reg_map* fsmcPsramRegion; + static bool fsmcInit = false; if (fsmcInit) return; - fsmcInit = 1; + fsmcInit = true; switch (cs) { case FSMC_CS_NE1: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION1; fsmcPsramRegion = FSMC_NOR_PSRAM1_BASE; break; @@ -179,35 +181,35 @@ void TFT_FSMC::Init() { LCD = (LCD_CONTROLLER_TypeDef*)controllerAddress; } -void TFT_FSMC::Transmit(uint16_t Data) { - LCD->RAM = Data; +void TFT_FSMC::transmit(uint16_t data) { + LCD->RAM = data; __DSB(); } -void TFT_FSMC::WriteReg(uint16_t Reg) { - LCD->REG = Reg; +void TFT_FSMC::writeReg(const uint16_t inReg) { + LCD->REG = inReg; __DSB(); } -uint32_t TFT_FSMC::GetID() { +uint32_t TFT_FSMC::getID() { uint32_t id; - WriteReg(0x0000); + writeReg(0x0000); id = LCD->RAM; if (id == 0) - id = ReadID(LCD_READ_ID); + id = readID(LCD_READ_ID); if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) - id = ReadID(LCD_READ_ID4); + id = readID(LCD_READ_ID4); if ((id & 0xFF00) == 0 && (id & 0xFF) != 0) - id = ReadID(LCD_READ_ID4); + id = readID(LCD_READ_ID4); return id; } - uint32_t TFT_FSMC::ReadID(uint16_t Reg) { + uint32_t TFT_FSMC::readID(const uint16_t inReg) { uint32_t id; - WriteReg(Reg); + writeReg(inReg); id = LCD->RAM; // dummy read - id = Reg << 24; + id = inReg << 24; id |= (LCD->RAM & 0x00FF) << 16; id |= (LCD->RAM & 0x00FF) << 8; id |= LCD->RAM & 0x00FF; @@ -215,23 +217,52 @@ uint32_t TFT_FSMC::GetID() { } bool TFT_FSMC::isBusy() { + #define __IS_DMA_CONFIGURED(__DMAx__, __CHx__) (dma_channel_regs(__DMAx__, __CHx__)->CPAR != 0) + + if (!__IS_DMA_CONFIGURED(FSMC_DMA_DEV, FSMC_DMA_CHANNEL)) return false; + + // Check if DMA transfer error or transfer complete flags are set + if ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & (DMA_ISR_TCIF | DMA_ISR_TEIF)) == 0) return true; + + __DSB(); + abort(); return false; } -void TFT_FSMC::Abort() { +void TFT_FSMC::abort() { + dma_channel_reg_map *channel_regs = dma_channel_regs(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); + dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); // Abort DMA transfer if any + + // Deconfigure DMA + channel_regs->CCR = 0U; + channel_regs->CNDTR = 0U; + channel_regs->CMAR = 0U; + channel_regs->CPAR = 0U; } -void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { +void TFT_FSMC::transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + // TODO: HAL STM32 uses DMA2_Channel1 for FSMC on STM32F1 + dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | memoryIncrease); + dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, count); + dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); + dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); + + TERN_(TFT_SHARED_IO, while (isBusy())); +} + +void TFT_FSMC::transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { #if defined(FSMC_DMA_DEV) && defined(FSMC_DMA_CHANNEL) - dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | MemoryIncrease); - dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Count); + dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | memoryIncrease); + dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, count); dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); - while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {}; - dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); + while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & (DMA_CCR_TEIE | DMA_CCR_TCIE)) == 0) {} + abort(); #endif } #endif // HAS_FSMC_TFT + +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h index d9ee1f4c77..214acf127e 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h @@ -30,9 +30,20 @@ #include +#ifndef FSMC_DMA_DEV + #define FSMC_DMA_DEV DMA2 +#endif +#ifndef FSMC_DMA_CHANNEL + #define FSMC_DMA_CHANNEL DMA_CH5 +#endif + #define DATASIZE_8BIT DMA_SIZE_8BITS #define DATASIZE_16BIT DMA_SIZE_16BITS #define TFT_IO_DRIVER TFT_FSMC +#define DMA_MAX_WORDS 0xFFFF + +#define DMA_PINC_ENABLE DMA_PINC_MODE +#define DMA_PINC_DISABLE 0 typedef struct { __IO uint16_t REG; @@ -43,29 +54,31 @@ class TFT_FSMC { private: static LCD_CONTROLLER_TypeDef *LCD; - static uint32_t ReadID(uint16_t Reg); - static void Transmit(uint16_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static uint32_t readID(const uint16_t inReg); + static void transmit(uint16_t data); + static void transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count); + static void transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count); public: - static void Init(); - static uint32_t GetID(); + static void init(); + static uint32_t getID(); static bool isBusy(); - static void Abort(); + static void abort(); - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT) {}; - static void DataTransferEnd() {}; + static void dataTransferBegin(uint16_t dataWidth=DATASIZE_16BIT) {}; + static void dataTransferEnd() {}; - static void WriteData(uint16_t Data) { Transmit(Data); } - static void WriteReg(uint16_t Reg); + static void writeData(uint16_t data) { transmit(data); } + static void writeReg(const uint16_t inReg); - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_MODE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); } - static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; - while (Count > 0) { - TransmitDMA(DMA_CIRC_MODE, &Data, Count > 0xFFFF ? 0xFFFF : Count); - Count = Count > 0xFFFF ? Count - 0xFFFF : 0; + static void writeSequence_DMA(uint16_t *data, uint16_t count) { transmitDMA(DMA_PINC_ENABLE, data, count); } + static void writeMultiple_DMA(uint16_t color, uint16_t count) { static uint16_t data; data = color; transmitDMA(DMA_PINC_DISABLE, &data, count); } + + static void writeSequence(uint16_t *data, uint16_t count) { transmit(DMA_PINC_ENABLE, data, count); } + static void writeMultiple(uint16_t color, uint32_t count) { + while (count > 0) { + transmit(DMA_PINC_DISABLE, &color, count > DMA_MAX_WORDS ? DMA_MAX_WORDS : count); + count = count > DMA_MAX_WORDS ? count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp index f447cec811..f26103b25d 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp @@ -20,15 +20,17 @@ * */ +#ifdef __STM32F1__ + #include "../../../inc/MarlinConfig.h" #if HAS_SPI_TFT #include "tft_spi.h" -SPIClass TFT_SPI::SPIx(1); +SPIClass TFT_SPI::SPIx(TFT_SPI_DEVICE); -void TFT_SPI::Init() { +void TFT_SPI::init() { #if PIN_EXISTS(TFT_RESET) OUT_WRITE(TFT_RESET_PIN, HIGH); delay(100); @@ -46,7 +48,7 @@ void TFT_SPI::Init() { * STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1 * so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2 */ - #if SPI_DEVICE == 1 + #if TFT_SPI_DEVICE == 1 #define SPI_CLOCK_MAX SPI_CLOCK_DIV4 #else #define SPI_CLOCK_MAX SPI_CLOCK_DIV2 @@ -62,27 +64,27 @@ void TFT_SPI::Init() { case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break; default: clock = SPI_CLOCK_DIV2; // Default from the SPI library } - SPIx.setModule(1); + SPIx.setModule(TFT_SPI_DEVICE); SPIx.setClockDivider(clock); SPIx.setBitOrder(MSBFIRST); SPIx.setDataMode(SPI_MODE0); } -void TFT_SPI::DataTransferBegin(uint16_t DataSize) { - SPIx.setDataSize(DataSize); +void TFT_SPI::dataTransferBegin(uint16_t dataSize) { + SPIx.setDataSize(dataSize); SPIx.begin(); - OUT_WRITE(TFT_CS_PIN, LOW); + WRITE(TFT_CS_PIN, LOW); } #ifdef TFT_DEFAULT_DRIVER #include "../../../lcd/tft_io/tft_ids.h" #endif -uint32_t TFT_SPI::GetID() { +uint32_t TFT_SPI::getID() { uint32_t id; - id = ReadID(LCD_READ_ID); + id = readID(LCD_READ_ID); if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { - id = ReadID(LCD_READ_ID4); + id = readID(LCD_READ_ID4); #ifdef TFT_DEFAULT_DRIVER if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) id = TFT_DEFAULT_DRIVER; @@ -91,39 +93,78 @@ uint32_t TFT_SPI::GetID() { return id; } -uint32_t TFT_SPI::ReadID(uint16_t Reg) { - #if !PIN_EXISTS(TFT_MISO) - return 0; - #else - uint8_t d = 0; - uint32_t data = 0; - SPIx.setClockDivider(SPI_CLOCK_DIV16); - DataTransferBegin(DATASIZE_8BIT); - WriteReg(Reg); +uint32_t TFT_SPI::readID(const uint16_t inReg) { + uint32_t data = 0; - LOOP_L_N(i, 4) { - SPIx.read((uint8_t*)&d, 1); + #if PIN_EXISTS(TFT_MISO) + SPIx.setClockDivider(SPI_CLOCK_DIV16); + dataTransferBegin(DATASIZE_8BIT); + writeReg(inReg); + + for (uint8_t i = 0; i < 4; ++i) { + uint8_t d; + SPIx.read(&d, 1); data = (data << 8) | d; } - DataTransferEnd(); + dataTransferEnd(); SPIx.setClockDivider(SPI_CLOCK_MAX); - - return data >> 7; #endif + + return data >> 7; } -bool TFT_SPI::isBusy() { return false; } +bool TFT_SPI::isBusy() { + #define __IS_DMA_CONFIGURED(__DMAx__, __CHx__) (dma_channel_regs(__DMAx__, __CHx__)->CPAR != 0) -void TFT_SPI::Abort() { DataTransferEnd(); } + if (!__IS_DMA_CONFIGURED(DMAx, DMA_CHx)) return false; -void TFT_SPI::Transmit(uint16_t Data) { SPIx.send(Data); } + if (dma_get_isr_bits(DMAx, DMA_CHx) & DMA_ISR_TEIF) { + // You should not be here - DMA transfer error flag is set + // Abort DMA transfer and release SPI + } + else { + // Check if DMA transfer completed flag is set + if (!(dma_get_isr_bits(DMAx, DMA_CHx) & DMA_ISR_TCIF)) return true; + // Check if SPI TX butter is empty and SPI is idle + if (!(SPIdev->regs->SR & SPI_SR_TXE) || (SPIdev->regs->SR & SPI_SR_BSY)) return true; + } -void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - DataTransferBegin(); - OUT_WRITE(TFT_DC_PIN, HIGH); - SPIx.dmaSend(Data, Count, MemoryIncrease == DMA_MINC_ENABLE); - DataTransferEnd(); + abort(); + return false; +} + +void TFT_SPI::abort() { + dma_channel_reg_map *channel_regs = dma_channel_regs(DMAx, DMA_CHx); + + dma_disable(DMAx, DMA_CHx); // Abort DMA transfer if any + spi_tx_dma_disable(SPIdev); + + // Deconfigure DMA + channel_regs->CCR = 0U; + channel_regs->CNDTR = 0U; + channel_regs->CMAR = 0U; + channel_regs->CPAR = 0U; + + dataTransferEnd(); +} + +void TFT_SPI::transmit(uint16_t data) { SPIx.send(data); } + +void TFT_SPI::transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + dataTransferBegin(); + SPIx.dmaSendAsync(data, count, memoryIncrease == DMA_MINC_ENABLE); + + TERN_(TFT_SHARED_IO, while (isBusy())); +} + +void TFT_SPI::transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { + WRITE(TFT_DC_PIN, HIGH); + dataTransferBegin(); + SPIx.dmaSend(data, count, memoryIncrease == DMA_MINC_ENABLE); + dataTransferEnd(); } #endif // HAS_SPI_TFT + +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.h b/Marlin/src/HAL/STM32F1/tft/tft_spi.h index da9a8e0c22..af53f352be 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.h @@ -25,6 +25,27 @@ #include +#define IS_SPI(N) (BOARD_NR_SPI >= N && (TFT_SCK_PIN == BOARD_SPI##N##_SCK_PIN) && (TFT_MOSI_PIN == BOARD_SPI##N##_MOSI_PIN) && (TFT_MISO_PIN == BOARD_SPI##N##_MISO_PIN)) +#if IS_SPI(1) + #define TFT_SPI_DEVICE 1 + #define SPIdev SPI1 + #define DMAx DMA1 + #define DMA_CHx DMA_CH3 +#elif IS_SPI(2) + #define TFT_SPI_DEVICE 2 + #define SPIdev SPI2 + #define DMAx DMA1 + #define DMA_CHx DMA_CH5 +#elif IS_SPI(3) + #define TFT_SPI_DEVICE 3 + #define SPIdev SPI3 + #define DMAx DMA2 + #define DMA_CHx DMA_CH2 +#else + #error "Invalid TFT SPI configuration." +#endif +#undef IS_SPI + #ifndef LCD_READ_ID #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) #endif @@ -32,41 +53,44 @@ #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) #endif -#define DATASIZE_8BIT DATA_SIZE_8BIT -#define DATASIZE_16BIT DATA_SIZE_16BIT -#define TFT_IO_DRIVER TFT_SPI +#define DATASIZE_8BIT DATA_SIZE_8BIT +#define DATASIZE_16BIT DATA_SIZE_16BIT +#define TFT_IO_DRIVER TFT_SPI +#define DMA_MAX_WORDS 0xFFFF -#define DMA_MINC_ENABLE 1 -#define DMA_MINC_DISABLE 0 +#define DMA_MINC_ENABLE DMA_MINC_MODE +#define DMA_MINC_DISABLE 0 class TFT_SPI { private: - static uint32_t ReadID(uint16_t Reg); - static void Transmit(uint16_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static uint32_t readID(const uint16_t inReg); + static void transmit(uint16_t data); + static void transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count); + static void transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count); public: static SPIClass SPIx; - static void Init(); - static uint32_t GetID(); + static void init(); + static uint32_t getID(); static bool isBusy(); - static void Abort(); + static void abort(); - static void DataTransferBegin(uint16_t DataWidth = DATA_SIZE_16BIT); - static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); SPIx.end(); }; - static void DataTransferAbort(); + static void dataTransferBegin(uint16_t dataWidth=DATA_SIZE_16BIT); + static void dataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); SPIx.end(); }; + static void dataTransferAbort(); - static void WriteData(uint16_t Data) { Transmit(Data); } - static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); } + static void writeData(uint16_t data) { transmit(data); } + static void writeReg(const uint16_t inReg) { WRITE(TFT_DC_PIN, LOW); transmit(inReg); WRITE(TFT_DC_PIN, HIGH); } - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } - static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; - while (Count > 0) { - TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); - Count = Count > 0xFFFF ? Count - 0xFFFF : 0; + static void writeSequence_DMA(uint16_t *data, uint16_t count) { transmitDMA(DMA_MINC_ENABLE, data, count); } + static void writeMultiple_DMA(uint16_t color, uint16_t count) { static uint16_t data; data = color; transmitDMA(DMA_MINC_DISABLE, &data, count); } + + static void writeSequence(uint16_t *data, uint16_t count) { transmit(DMA_MINC_ENABLE, data, count); } + static void writeMultiple(uint16_t color, uint32_t count) { + while (count > 0) { + transmit(DMA_MINC_DISABLE, &color, count > DMA_MAX_WORDS ? DMA_MAX_WORDS : count); + count = count > DMA_MAX_WORDS ? count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp index ac9ad072aa..475290de45 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp @@ -20,6 +20,8 @@ * */ +#ifdef __STM32F1__ + #include "../../../inc/MarlinConfig.h" #if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS @@ -57,7 +59,7 @@ uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } } #endif // TOUCH_BUTTONS_HW_SPI -void XPT2046::Init() { +void XPT2046::init() { SET_INPUT(TOUCH_MISO_PIN); SET_OUTPUT(TOUCH_MOSI_PIN); SET_OUTPUT(TOUCH_SCK_PIN); @@ -84,9 +86,8 @@ bool XPT2046::isTouched() { ); } -bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { - if (isBusy()) return false; - if (!isTouched()) return false; +bool XPT2046::getRawPoint(int16_t * const x, int16_t * const y) { + if (isBusy() || !isTouched()) return false; *x = getRawData(XPT2046_X); *y = getRawData(XPT2046_Y); return isTouched(); @@ -95,7 +96,7 @@ bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { uint16_t data[3]; - DataTransferBegin(); + dataTransferBegin(); TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.begin()); for (uint16_t i = 0; i < 3 ; i++) { @@ -104,7 +105,7 @@ uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { } TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.end()); - DataTransferEnd(); + dataTransferEnd(); uint16_t delta01 = delta(data[0], data[1]), delta02 = delta(data[0], data[2]), @@ -117,17 +118,17 @@ uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { } uint16_t XPT2046::IO(uint16_t data) { - return TERN(TOUCH_BUTTONS_HW_SPI, HardwareIO, SoftwareIO)(data); + return TERN(TOUCH_BUTTONS_HW_SPI, hardwareIO, softwareIO)(data); } #if ENABLED(TOUCH_BUTTONS_HW_SPI) - uint16_t XPT2046::HardwareIO(uint16_t data) { + uint16_t XPT2046::hardwareIO(uint16_t data) { uint16_t result = SPIx.transfer(data); return result; } #endif -uint16_t XPT2046::SoftwareIO(uint16_t data) { +uint16_t XPT2046::softwareIO(uint16_t data) { uint16_t result = 0; for (uint8_t j = 0x80; j; j >>= 1) { @@ -141,4 +142,6 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) { return result; } -#endif // HAS_TFT_XPT2046 +#endif // HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS + +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.h b/Marlin/src/HAL/STM32F1/tft/xpt2046.h index 7c456cf00e..9a19e3c98d 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.h @@ -65,12 +65,12 @@ private: static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; - static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; + static void dataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; + static void dataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static uint16_t HardwareIO(uint16_t data); + static uint16_t hardwareIO(uint16_t data); #endif - static uint16_t SoftwareIO(uint16_t data); + static uint16_t softwareIO(uint16_t data); static uint16_t IO(uint16_t data = 0); public: @@ -78,6 +78,6 @@ public: static SPIClass SPIx; #endif - static void Init(); - static bool getRawPoint(int16_t *x, int16_t *y); + static void init(); + static bool getRawPoint(int16_t * const x, int16_t * const y); }; diff --git a/Marlin/src/HAL/STM32F1/timers.cpp b/Marlin/src/HAL/STM32F1/timers.cpp index 112c730b9a..141dc80b80 100644 --- a/Marlin/src/HAL/STM32F1/timers.cpp +++ b/Marlin/src/HAL/STM32F1/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -84,7 +84,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { timer_set_prescaler(STEP_TIMER_DEV, (uint16_t)(STEPPER_TIMER_PRESCALE - 1)); timer_set_reload(STEP_TIMER_DEV, 0xFFFF); timer_oc_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OC_MODE_FROZEN, TIMER_OC_NO_PRELOAD); // no output pin change - timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency)); + timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(HAL_TIMER_TYPE_MAX, hal_timer_t((STEPPER_TIMER_RATE) / frequency))); timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler); HAL_timer_set_interrupt_priority(MF_TIMER_STEP, STEP_TIMER_IRQ_PRIO); @@ -97,7 +97,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { timer_set_count(TEMP_TIMER_DEV, 0); timer_set_prescaler(TEMP_TIMER_DEV, (uint16_t)(TEMP_TIMER_PRESCALE - 1)); timer_set_reload(TEMP_TIMER_DEV, 0xFFFF); - timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency)); + timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(HAL_TIMER_TYPE_MAX, hal_timer_t((F_CPU) / (TEMP_TIMER_PRESCALE) / frequency))); timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler); HAL_timer_set_interrupt_priority(MF_TIMER_TEMP, TEMP_TIMER_IRQ_PRIO); timer_generate_update(TEMP_TIMER_DEV); diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 0cd807fc84..3d6650a1a2 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -40,7 +40,7 @@ */ typedef uint16_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) #define HAL_TIMER_RATE uint32_t(F_CPU) // frequency of timers peripherals @@ -80,8 +80,8 @@ typedef uint16_t hal_timer_t; //#define MF_TIMER_TEMP 4 // 2->4, Timer 2 for Stepper Current PWM #endif -#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3) - // SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM. +#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3, VOXELAB_AQUILA) + // SKR Mini E3 boards use PA8 as FAN0_PIN, so TIMER 1 is used for Fan PWM. #ifdef STM32_HIGH_DENSITY #define MF_TIMER_SERVO0 8 // tone.cpp uses Timer 4 #else @@ -95,27 +95,26 @@ typedef uint16_t hal_timer_t; #define TEMP_TIMER_IRQ_PRIO 3 #define SERVO0_TIMER_IRQ_PRIO 1 -#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_PRESCALE 1000 // Prescaler for setting Temp Timer, 72Khz +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_PRESCALE 18 // prescaler for setting stepper timer, 4Mhz -#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_PRESCALE 18 // Prescaler for setting stepper timer, 4Mhz +#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // (Hz) Frequency of Stepper Timer ISR +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US timer_dev* HAL_get_timer_dev(int number); #define TIMER_DEV(num) HAL_get_timer_dev(num) #define STEP_TIMER_DEV TIMER_DEV(MF_TIMER_STEP) #define TEMP_TIMER_DEV TIMER_DEV(MF_TIMER_TEMP) -#define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN) +#define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN) #define DISABLE_TEMPERATURE_INTERRUPT() timer_disable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN) #define HAL_timer_get_count(timer_num) timer_get_count(TIMER_DEV(timer_num)) @@ -188,7 +187,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // Needed here to reset ARPE=0 for stepper timer diff --git a/Marlin/src/HAL/STM32F1/u8g/LCD_defines.h b/Marlin/src/HAL/STM32F1/u8g/LCD_defines.h new file mode 100644 index 0000000000..9d0137ae6a --- /dev/null +++ b/Marlin/src/HAL/STM32F1/u8g/LCD_defines.h @@ -0,0 +1,34 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * STM32F1 (Maple) LCD-specific defines + */ + +uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // u8g_com_stm32duino_swspi.cpp +uint8_t u8g_com_stm32duino_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // See U8glib-HAL + +#define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_STM32F1_sw_spi_fn +#define U8G_COM_HAL_HW_SPI_FN u8g_com_stm32duino_hw_spi_fn // See U8glib-HAL +#define U8G_COM_ST7920_HAL_SW_SPI u8g_com_std_sw_spi_fn // See U8glib-HAL +#define U8G_COM_ST7920_HAL_HW_SPI u8g_com_stm32duino_hw_spi_fn // See U8glib-HAL diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/u8g/u8g_com_stm32duino_swspi.cpp similarity index 77% rename from Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp rename to Marlin/src/HAL/STM32F1/u8g/u8g_com_stm32duino_swspi.cpp index 26ea1ea19a..28302edaf5 100644 --- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/u8g/u8g_com_stm32duino_swspi.cpp @@ -24,7 +24,7 @@ #include "../../../inc/MarlinConfig.h" -#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) +#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) #include #include "../../shared/HAL_SPI.h" @@ -37,7 +37,7 @@ static uint8_t SPI_speed = LCD_SPI_SPEED; static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { WRITE(DOGLCD_MOSI, !!(b & 0x80)); WRITE(DOGLCD_SCK, HIGH); @@ -47,16 +47,16 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_MOSI, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE(DOGLCD_SCK, HIGH); b <<= 1; if (miso_pin >= 0 && READ(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_SCK, LOW); } } @@ -64,7 +64,7 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c } static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { WRITE(DOGLCD_SCK, LOW); @@ -73,13 +73,13 @@ static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, c WRITE(DOGLCD_SCK, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE(DOGLCD_SCK, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_MOSI, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_SCK, HIGH); } b <<= 1; @@ -88,8 +88,8 @@ static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, c return b; } -static void u8g_sw_spi_HAL_STM32F1_shift_out(uint8_t val) { - #if ENABLED(FYSETC_MINI_12864) +static void u8g_sw_spi_shift_out(uint8_t val) { + #if U8G_SPI_USE_MODE_3 swSpiTransfer_mode_3(val, SPI_speed); #else swSpiTransfer_mode_0(val, SPI_speed); @@ -123,15 +123,15 @@ uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, break; case U8G_COM_MSG_CHIP_SELECT: - #if ENABLED(FYSETC_MINI_12864) // This LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - WRITE(DOGLCD_SCK, HIGH); // Set SCK to mode 3 idle state before CS goes active + #if U8G_SPI_USE_MODE_3 // This LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + WRITE(DOGLCD_SCK, HIGH); // Set SCK to mode 3 idle state before CS goes active WRITE(DOGLCD_CS, LOW); } else { WRITE(DOGLCD_CS, HIGH); - WRITE(DOGLCD_SCK, LOW); // Set SCK to mode 0 idle state after CS goes inactive + WRITE(DOGLCD_SCK, LOW); // Set SCK to mode 0 idle state after CS goes inactive } #else WRITE(DOGLCD_CS, !arg_val); @@ -139,13 +139,13 @@ uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, break; case U8G_COM_MSG_WRITE_BYTE: - u8g_sw_spi_HAL_STM32F1_shift_out(arg_val); + u8g_sw_spi_shift_out(arg_val); break; case U8G_COM_MSG_WRITE_SEQ: { uint8_t *ptr = (uint8_t *)arg_ptr; while (arg_val > 0) { - u8g_sw_spi_HAL_STM32F1_shift_out(*ptr++); + u8g_sw_spi_shift_out(*ptr++); arg_val--; } } break; @@ -153,7 +153,7 @@ uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, case U8G_COM_MSG_WRITE_SEQ_P: { uint8_t *ptr = (uint8_t *)arg_ptr; while (arg_val > 0) { - u8g_sw_spi_HAL_STM32F1_shift_out(u8g_pgm_read(ptr)); + u8g_sw_spi_shift_out(u8g_pgm_read(ptr)); ptr++; arg_val--; } diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp index 2892368967..f54025991d 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp @@ -37,10 +37,20 @@ #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) -#if WITHIN(SERIAL_PORT, 0, 3) +#if WITHIN(SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) IMPLEMENT_SERIAL(SERIAL_PORT); -#else - #error "SERIAL_PORT must be from 0 to 3." +#endif +#if defined(SERIAL_PORT_2) && WITHIN(SERIAL_PORT_2, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(SERIAL_PORT_2); +#endif +#if defined(SERIAL_PORT_3) && WITHIN(SERIAL_PORT_3, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(SERIAL_PORT_3); +#endif +#if defined(MMU_SERIAL_PORT) && WITHIN(MMU_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(MMU_SERIAL_PORT); +#endif +#if defined(LCD_SERIAL_PORT) && WITHIN(LCD_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(LCD_SERIAL_PORT); #endif USBSerialType USBSerial(false, SerialUSB); diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index a7aa9f0da2..b98ee9eb39 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -64,17 +64,10 @@ typedef ForwardSerial1Class USBSerialType; extern USBSerialType USBSerial; -#define _MSERIAL(X) MSerial##X -#define MSERIAL(X) _MSERIAL(X) - -#if SERIAL_PORT == -1 - #define MYSERIAL1 USBSerial -#elif WITHIN(SERIAL_PORT, 0, 3) - DECLARE_SERIAL(SERIAL_PORT); - #define MYSERIAL1 MSERIAL(SERIAL_PORT) -#else - #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." -#endif +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 3 +#define USB_SERIAL_PORT(...) USBSerial +#include "../shared/serial_ports.h" // ------------------------ // Types @@ -98,10 +91,10 @@ uint32_t __get_PRIMASK(void); // CMSIS // ------------------------ #ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) + #define analogInputToDigitalPin(p) pin_t((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 // @@ -149,7 +142,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index 415c692229..cda7e7d16c 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -120,7 +120,6 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.endTransaction(); } - // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { spiConfig = SPISettings(spiClock, bitOrder, dataMode); diff --git a/Marlin/src/HAL/TEENSY31_32/Servo.h b/Marlin/src/HAL/TEENSY31_32/Servo.h index 82b601d956..2da74fd25d 100644 --- a/Marlin/src/HAL/TEENSY31_32/Servo.h +++ b/Marlin/src/HAL/TEENSY31_32/Servo.h @@ -31,7 +31,5 @@ class libServo : public Servo { void move(const int value); private: typedef Servo super; - uint16_t min_ticks; - uint16_t max_ticks; uint8_t servoIndex; // index into the channel data for this servo }; diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp index d1ff940822..a7e5e590a3 100644 --- a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp @@ -36,7 +36,7 @@ #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(E2END + 1) #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } @@ -44,7 +44,7 @@ bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { uint16_t written = 0; while (size--) { - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); uint8_t v = *value; if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); @@ -63,7 +63,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t c = eeprom_read_byte((uint8_t*)pos); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h index c1bbcb121b..798ca4f0cb 100644 --- a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h @@ -47,33 +47,34 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); - TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY31_32/fastio.h b/Marlin/src/HAL/TEENSY31_32/fastio.h index 622799ec8c..b582c7bfec 100644 --- a/Marlin/src/HAL/TEENSY31_32/fastio.h +++ b/Marlin/src/HAL/TEENSY31_32/fastio.h @@ -53,17 +53,17 @@ #define _SET_INPUT(P) do{ \ CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1); \ - GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 0; \ + GPIO_BITBAND(CORE_PIN ## P ## _DDRREG, CORE_PIN ## P ## _BIT) = 0; \ }while(0) #define _SET_OUTPUT(P) do{ \ CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1)|PORT_PCR_SRE|PORT_PCR_DSE; \ - GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 1; \ + GPIO_BITBAND(CORE_PIN ## P ## _DDRREG, CORE_PIN ## P ## _BIT) = 1; \ }while(0) #define _SET_INPUT_PULLUP(P) do{ \ CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1) | PORT_PCR_PE | PORT_PCR_PS; \ - GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 0; \ + GPIO_BITBAND(CORE_PIN ## P ## _DDRREG, CORE_PIN ## P ## _BIT) = 0; \ }while(0) #define _IS_INPUT(P) ((CORE_PIN ## P ## _DDRREG & CORE_PIN ## P ## _BITMASK) == 0) diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h index 54ec166643..5f1c4b1601 100644 --- a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h @@ -20,7 +20,3 @@ * */ #pragma once - -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/TEENSY31_32." -#endif diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_type.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h index dbce187673..c5b25f2cb5 100644 --- a/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h +++ b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h @@ -25,22 +25,26 @@ * Test TEENSY35_36 specific configuration values for errors at compile-time. */ +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for Teensy 3.1/3.2." +#endif + #if ENABLED(EMERGENCY_PARSER) #error "EMERGENCY_PARSER is not yet implemented for Teensy 3.1/3.2. Disable EMERGENCY_PARSER to continue." #endif #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on Teensy 3.1/3.2." + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported for Teensy 3.1/3.2." #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on Teensy 3.1/3.2." + #error "TMC220x Software Serial is not supported for Teensy 3.1/3.2." #endif #if ENABLED(POSTMORTEM_DEBUGGING) - #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 3.1/3.2." + #error "POSTMORTEM_DEBUGGING is not yet supported for Teensy 3.1/3.2." #endif #if USING_PULLDOWNS - #error "PULLDOWN pin mode is not available on Teensy 3.1/3.2 boards." + #error "PULLDOWN pin mode is not available for Teensy 3.1/3.2." #endif diff --git a/Marlin/src/HAL/TEENSY31_32/pinsDebug.h b/Marlin/src/HAL/TEENSY31_32/pinsDebug.h index d4a91ce801..741909bf0a 100644 --- a/Marlin/src/HAL/TEENSY31_32/pinsDebug.h +++ b/Marlin/src/HAL/TEENSY31_32/pinsDebug.h @@ -1 +1,71 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + #error "PINS_DEBUGGING is not yet supported for Teensy 3.1 / 3.2!" + +/** + * Pins Debugging for ESP32 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS +#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin + +#define digitalRead_mod(P) extDigitalRead(P) +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define getPinByIndex(x) pin_array[x].pin +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL)) +#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0)) +#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1))) +bool pwm_status(const pin_t) { return false; } + +void printPinPort(const pin_t) {} + +static bool getValidPinMode(const pin_t pin) { + return isValidPin(pin) /* && !IS_INPUT(pin) */ ; +} + +void printPinPWM(const int32_t pin) { + if (pwm_status(pin)) { + //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative; + //SERIAL_ECHOPGM("PWM = ", duty); + } +} diff --git a/Marlin/src/HAL/TEENSY31_32/spi_pins.h b/Marlin/src/HAL/TEENSY31_32/spi_pins.h index 6d0d05f85a..dbd0bb9174 100644 --- a/Marlin/src/HAL/TEENSY31_32/spi_pins.h +++ b/Marlin/src/HAL/TEENSY31_32/spi_pins.h @@ -24,4 +24,3 @@ #define SD_SCK_PIN 13 #define SD_MISO_PIN 12 #define SD_MOSI_PIN 11 -#define SD_SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 9fcbb6f232..cdca84ec1c 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -34,14 +34,14 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define FTM0_TIMER_PRESCALE 8 #define FTM1_TIMER_PRESCALE 4 #define FTM0_TIMER_PRESCALE_BITS 0b011 #define FTM1_TIMER_PRESCALE_BITS 0b010 -#define FTM0_TIMER_RATE (F_BUS / (FTM0_TIMER_PRESCALE)) // 60MHz / 8 = 7500kHz +#define FTM0_TIMER_RATE (F_BUS / (FTM0_TIMER_PRESCALE)) // 60MHz / 8 = 7.5MHz #define FTM1_TIMER_RATE (F_BUS / (FTM1_TIMER_PRESCALE)) // 60MHz / 4 = 15MHz #define HAL_TIMER_RATE (FTM0_TIMER_RATE) @@ -58,26 +58,25 @@ typedef uint32_t hal_timer_t; #define TEMP_TIMER_FREQUENCY 1000 -#define STEPPER_TIMER_RATE HAL_TIMER_RATE -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() + #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() + #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() #endif void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); @@ -110,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/TEENSY31_32/u8g/LCD_defines.h b/Marlin/src/HAL/TEENSY31_32/u8g/LCD_defines.h new file mode 100644 index 0000000000..a13e7e837f --- /dev/null +++ b/Marlin/src/HAL/TEENSY31_32/u8g/LCD_defines.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Teensy 3.1/3.2 LCD-specific defines + */ diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp index bc02ac1c45..f41582be30 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp @@ -37,10 +37,21 @@ #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) -#if WITHIN(SERIAL_PORT, 0, 3) +#if WITHIN(SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) IMPLEMENT_SERIAL(SERIAL_PORT); #endif - +#if defined(SERIAL_PORT_2) && WITHIN(SERIAL_PORT_2, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(SERIAL_PORT_2); +#endif +#if defined(SERIAL_PORT_3) && WITHIN(SERIAL_PORT_3, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(SERIAL_PORT_3); +#endif +#if defined(MMU_SERIAL_PORT) && WITHIN(MMU_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(MMU_SERIAL_PORT); +#endif +#if defined(LCD_SERIAL_PORT) && WITHIN(LCD_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(LCD_SERIAL_PORT); +#endif USBSerialType USBSerial(false, SerialUSB); // ------------------------ diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 2a192e4718..85d02cec8c 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -70,17 +70,10 @@ typedef ForwardSerial1Class USBSerialType; extern USBSerialType USBSerial; -#define _MSERIAL(X) MSerial##X -#define MSERIAL(X) _MSERIAL(X) - -#if SERIAL_PORT == -1 - #define MYSERIAL1 USBSerial -#elif WITHIN(SERIAL_PORT, 0, 3) - #define MYSERIAL1 MSERIAL(SERIAL_PORT) - DECLARE_SERIAL(SERIAL_PORT); -#else - #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB." -#endif +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 3 +#define USB_SERIAL_PORT(...) USBSerial +#include "../shared/serial_ports.h" // ------------------------ // Types @@ -103,10 +96,10 @@ typedef int8_t pin_t; // ------------------------ #ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) + #define analogInputToDigitalPin(p) pin_t((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 // @@ -154,7 +147,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/TEENSY35_36/Servo.h b/Marlin/src/HAL/TEENSY35_36/Servo.h index 719011f102..c37567a813 100644 --- a/Marlin/src/HAL/TEENSY35_36/Servo.h +++ b/Marlin/src/HAL/TEENSY35_36/Servo.h @@ -35,7 +35,5 @@ class libServo : public Servo { void move(const int value); private: typedef Servo super; - uint16_t min_ticks; - uint16_t max_ticks; uint8_t servoIndex; // Index into the channel data for this servo }; diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index b80e93b536..977cd70ee8 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -36,7 +35,7 @@ #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(E2END + 1) #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } @@ -44,7 +43,7 @@ bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { uint16_t written = 0; while (size--) { - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); uint8_t v = *value; if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); @@ -63,7 +62,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t c = eeprom_read_byte((uint8_t*)pos); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h index 48d3bbbfa1..a938041b5a 100644 --- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h @@ -46,33 +46,34 @@ void endstop_ISR() { endstops.update(); } */ void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); - TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY35_36/fastio.h b/Marlin/src/HAL/TEENSY35_36/fastio.h index 622799ec8c..b582c7bfec 100644 --- a/Marlin/src/HAL/TEENSY35_36/fastio.h +++ b/Marlin/src/HAL/TEENSY35_36/fastio.h @@ -53,17 +53,17 @@ #define _SET_INPUT(P) do{ \ CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1); \ - GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 0; \ + GPIO_BITBAND(CORE_PIN ## P ## _DDRREG, CORE_PIN ## P ## _BIT) = 0; \ }while(0) #define _SET_OUTPUT(P) do{ \ CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1)|PORT_PCR_SRE|PORT_PCR_DSE; \ - GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 1; \ + GPIO_BITBAND(CORE_PIN ## P ## _DDRREG, CORE_PIN ## P ## _BIT) = 1; \ }while(0) #define _SET_INPUT_PULLUP(P) do{ \ CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1) | PORT_PCR_PE | PORT_PCR_PS; \ - GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 0; \ + GPIO_BITBAND(CORE_PIN ## P ## _DDRREG, CORE_PIN ## P ## _BIT) = 0; \ }while(0) #define _IS_INPUT(P) ((CORE_PIN ## P ## _DDRREG & CORE_PIN ## P ## _BITMASK) == 0) diff --git a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h index 632ee533ac..5f1c4b1601 100644 --- a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h @@ -20,7 +20,3 @@ * */ #pragma once - -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/TEENSY35_36." -#endif diff --git a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_type.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h index 3308707371..8f2651d3ed 100644 --- a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h +++ b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h @@ -25,22 +25,30 @@ * Test TEENSY35_36 specific configuration values for errors at compile-time. */ +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for Teensy 3.5/3.6." +#endif + #if ENABLED(EMERGENCY_PARSER) #error "EMERGENCY_PARSER is not yet implemented for Teensy 3.5/3.6. Disable EMERGENCY_PARSER to continue." #endif #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on Teensy 3.5/3.6." + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported for Teensy 3.5/3.6." #endif #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on Teensy 3.5/3.6." + #error "TMC220x Software Serial is not supported for Teensy 3.5/3.6." #endif #if ENABLED(POSTMORTEM_DEBUGGING) - #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 3.5/3.6." + #error "POSTMORTEM_DEBUGGING is not yet supported for Teensy 3.5/3.6." #endif #if USING_PULLDOWNS - #error "PULLDOWN pin mode is not available on Teensy 3.5/3.6 boards." + #error "PULLDOWN pin mode is not available for Teensy 3.5/3.6." +#endif + +#if ENABLED(PINS_DEBUGGING) + #error "PINS_DEBUGGING is not yet supported for Teensy 3.5/3.6. Needs is_output(pin), etc." #endif diff --git a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h index 7a2e1d6e59..f0f61b8bbe 100644 --- a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h +++ b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h @@ -22,7 +22,23 @@ #pragma once /** - * HAL Pins Debugging for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0) + * Pins Debugging for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0) + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) */ #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS @@ -53,14 +69,23 @@ #define TPM1_CH1_PIN 17 #endif -#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20)) +#define getPinByIndex(x) pin_array[x].pin +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0)) +#define getValidPinMode(P) (isValidPin(P) && IS_OUTPUT(P)) +#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL)) +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) -void HAL_print_analog_pin(char buffer[], int8_t pin) { +#define isAnalogPin(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20)) + +void printAnalogPin(char buffer[], int8_t pin) { if (pin <= 23) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 14)); else if (pin <= 39) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 19)); } -void HAL_analog_pin_state(char buffer[], int8_t pin) { +void analog_pin_state(char buffer[], int8_t pin) { if (pin <= 23) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 14)); else if (pin <= 39) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 19)); } @@ -77,7 +102,7 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) { * Print a pin's PWM status. * Return true if it's currently a PWM pin. */ -bool HAL_pwm_status(int8_t pin) { +bool pwm_status(const int8_t pin) { char buffer[20]; // for the sprintf statements switch (pin) { FTM_CASE(0,0); @@ -108,4 +133,6 @@ bool HAL_pwm_status(int8_t pin) { SERIAL_ECHOPGM(" "); } -static void HAL_pwm_details(uint8_t pin) { /* TODO */ } +void printPinPWM(const pin_t) { /* TODO */ } + +void printPinPort(const pin_t) {} diff --git a/Marlin/src/HAL/TEENSY35_36/spi_pins.h b/Marlin/src/HAL/TEENSY35_36/spi_pins.h index cfffdc9325..d898a923f5 100644 --- a/Marlin/src/HAL/TEENSY35_36/spi_pins.h +++ b/Marlin/src/HAL/TEENSY35_36/spi_pins.h @@ -28,4 +28,3 @@ #define SD_SCK_PIN 13 #define SD_MISO_PIN 12 #define SD_MOSI_PIN 11 -#define SD_SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 8af79d7392..1a5a8460c6 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -33,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define FTM0_TIMER_PRESCALE 8 #define FTM1_TIMER_PRESCALE 4 @@ -57,19 +58,18 @@ typedef uint32_t hal_timer_t; #define TEMP_TIMER_FREQUENCY 1000 -#define STEPPER_TIMER_RATE HAL_TIMER_RATE -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR @@ -109,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/TEENSY35_36/u8g/LCD_defines.h b/Marlin/src/HAL/TEENSY35_36/u8g/LCD_defines.h new file mode 100644 index 0000000000..511085781c --- /dev/null +++ b/Marlin/src/HAL/TEENSY35_36/u8g/LCD_defines.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Teensy 3.5/3.6 LCD-specific defines + */ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 1d02ab8575..3a1f06095b 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -39,9 +39,21 @@ #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) -#if WITHIN(SERIAL_PORT, 0, 3) +#if WITHIN(SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) IMPLEMENT_SERIAL(SERIAL_PORT); #endif +#if defined(SERIAL_PORT_2) && WITHIN(SERIAL_PORT_2, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(SERIAL_PORT_2); +#endif +#if defined(SERIAL_PORT_3) && WITHIN(SERIAL_PORT_3, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(SERIAL_PORT_3); +#endif +#if defined(MMU_SERIAL_PORT) && WITHIN(MMU_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(MMU_SERIAL_PORT); +#endif +#if defined(LCD_SERIAL_PORT) && WITHIN(LCD_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + IMPLEMENT_SERIAL(LCD_SERIAL_PORT); +#endif USBSerialType USBSerial(false, SerialUSB); // ------------------------ @@ -86,7 +98,7 @@ void MarlinHAL::clear_reset_source() { #define WDT_TIMEOUT TERN(WATCHDOG_DURATION_8S, 8, 4) // 4 or 8 second timeout - constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) / 0.5f; + constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) * 2.0f; void MarlinHAL::watchdog_init() { CCM_CCGR3 |= CCM_CCGR3_WDOG1(3); // enable WDOG1 clocks @@ -192,18 +204,13 @@ uint16_t MarlinHAL::adc_value() { // Free Memory Accessor // ------------------------ -#define __bss_end _ebss - extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; + // Reference for Teensy 4.x: https://forum.pjrc.com/index.php?threads/how-to-display-free-ram.33443/#post-275013 + extern unsigned long _heap_end; + extern char *__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; + return (char *)&_heap_end - __brkval; } } diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index c54a2e8a0b..fc75539e9b 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -61,6 +61,8 @@ #undef PSTR #define PSTR(str) ({static const char *data = (str); &data[0];}) +#define HAL_CAN_SET_PWM_FREQ + // ------------------------ // Serial ports // ------------------------ @@ -76,29 +78,11 @@ typedef ForwardSerial1Class USBSerialType; extern USBSerialType USBSerial; -#define _MSERIAL(X) MSerial##X -#define MSERIAL(X) _MSERIAL(X) - -#if SERIAL_PORT == -1 - #define MYSERIAL1 SerialUSB -#elif WITHIN(SERIAL_PORT, 0, 8) - DECLARE_SERIAL(SERIAL_PORT); - #define MYSERIAL1 MSERIAL(SERIAL_PORT) -#else - #error "The required SERIAL_PORT must be from 0 to 8, or -1 for Native USB." -#endif - -#ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == -1 - #define MYSERIAL2 usbSerial - #elif SERIAL_PORT_2 == -2 - #define MYSERIAL2 ethernet.telnetClient - #elif WITHIN(SERIAL_PORT_2, 0, 8) - #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) - #else - #error "SERIAL_PORT_2 must be from 0 to 8, or -1 for Native USB, or -2 for Ethernet." - #endif -#endif +#define SERIAL_INDEX_MIN 0 +#define SERIAL_INDEX_MAX 8 +#define USB_SERIAL_PORT(...) USBSerial +#define ETH_SERIAL_PORT(...) ethernet.telnetClient +#include "../shared/serial_ports.h" // ------------------------ // Types @@ -121,10 +105,10 @@ typedef int8_t pin_t; // ------------------------ #ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) + #define analogInputToDigitalPin(p) pin_t((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 #define HAL_ADC_FILTERED // turn off ADC oversampling @@ -176,7 +160,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset @@ -209,11 +193,15 @@ public: /** * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + * Optionally invert the duty cycle [default = false] + * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + /** + * Set the PWM output frequency. This may affect multiple pins, though + * Teensy 4.x provides many timers affecting only a single pin. + * See: https://www.pjrc.com/teensy/td_pulse.html + */ + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); }; diff --git a/Marlin/src/HAL/TEENSY40_41/Servo.h b/Marlin/src/HAL/TEENSY40_41/Servo.h index 699fd700c9..fceb9465ea 100644 --- a/Marlin/src/HAL/TEENSY40_41/Servo.h +++ b/Marlin/src/HAL/TEENSY40_41/Servo.h @@ -37,7 +37,5 @@ class libServo : public PWMServo { private: typedef PWMServo super; uint8_t servoPin; - uint16_t min_ticks; - uint16_t max_ticks; uint8_t servoIndex; // Index into the channel data for this servo }; diff --git a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp index 3cd376edce..357fed47b0 100644 --- a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -36,7 +35,7 @@ #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(E2END + 1) #endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE - eeprom_exclude_size; } bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } @@ -44,7 +43,7 @@ bool PersistentStore::access_finish() { return true; } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { uint16_t written = 0; while (size--) { - uint8_t * const p = (uint8_t * const)pos; + uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos); uint8_t v = *value; if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! eeprom_write_byte(p, v); @@ -63,7 +62,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - uint8_t c = eeprom_read_byte((uint8_t*)pos); + const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos)); if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h index 4c3ddec9f1..f59a9409c8 100644 --- a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h @@ -46,27 +46,34 @@ void endstop_ISR() { endstops.update(); } */ void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); - TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY40_41/fast_pwm.cpp b/Marlin/src/HAL/TEENSY40_41/fast_pwm.cpp new file mode 100644 index 0000000000..21531d115d --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/fast_pwm.cpp @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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__ + +#include "../../inc/MarlinConfig.h" + +#include "HAL.h" + +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size /*=255*/, const bool invert) { + + uint32_t bits = 1; + uint16_t value = _MIN(v, v_size); + + if (invert) value = v_size - value; + + // Choose scale as smallest power of 2 which holds v_size. + uint32_t scale = 1; + while (scale < v_size) { + bits++; + scale *= 2; + } + + uint32_t scaled_val = scale * value / v_size; + + uint32_t prior = analogWriteResolution(bits); + analogWrite(pin, scaled_val); + analogWriteResolution(prior); +} + +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { + analogWriteFrequency(pin, f_desired); +} + +#endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/fastio.h b/Marlin/src/HAL/TEENSY40_41/fastio.h index 52f991dfb8..179f044c9b 100644 --- a/Marlin/src/HAL/TEENSY40_41/fastio.h +++ b/Marlin/src/HAL/TEENSY40_41/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h index 6a8540927b..5f1c4b1601 100644 --- a/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h @@ -20,7 +20,3 @@ * */ #pragma once - -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/TEENSY40_41." -#endif diff --git a/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_type.h b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_type.h new file mode 100644 index 0000000000..82f95a1035 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_type.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 diff --git a/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h index 3d2668d749..7b1c466f23 100644 --- a/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h +++ b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h @@ -25,18 +25,34 @@ * Test TEENSY41 specific configuration values for errors at compile-time. */ +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for Teensy 4.0/4.1." +#endif + #if ENABLED(EMERGENCY_PARSER) #error "EMERGENCY_PARSER is not yet implemented for Teensy 4.0/4.1. Disable EMERGENCY_PARSER to continue." #endif -#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY - #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on Teensy 4.0/4.1." -#endif - #if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on Teensy 4.0/4.1." + #error "TMC220x Software Serial is not supported for Teensy 4.0/4.1." #endif #if ENABLED(POSTMORTEM_DEBUGGING) - #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 4.0/4.1." + #error "POSTMORTEM_DEBUGGING is not yet supported for Teensy 4.0/4.1." +#endif + +#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) || ENABLED(SERIAL_STATS_DROPPED_RX) || ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS) || ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS) + #error "SERIAL_STATS_* features not supported on Teensy 4.0/4.1." +#endif + +#if ENABLED(BAUD_RATE_GCODE) && SERIAL_PORT_2 == -2 + #error "BAUD_RATE_GCODE cannot be enabled when using the Ethernet serial port." +#endif + +#if ENABLED(SPINDLE_LASER_USE_PWM) && !ENABLED(SILENCE_TEENSY_SPINDLE_LASER_WARNING) + #warning "SPINDLE_LASER_USE_PWM is untested on Teensy 4.0/4.1, see https://www.pjrc.com/teensy/td_pulse.html for details on frequencies, and resolution. #define SILENCE_TEENSY_SPINDLE_LASER_WARNING to silence warning." +#endif + +#if ENABLED(FAST_PWM_FAN) && FAST_PWM_FAN_FREQUENCY == 1000U + #warning "FAST_PWM_FAN_FREQUENCY has been left as default, see https://www.pjrc.com/teensy/td_pulse.html and consider raising it to reduce noise." #endif diff --git a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h index 94b85ea568..3307b3f71f 100644 --- a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h +++ b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h @@ -22,25 +22,39 @@ #pragma once /** - * HAL Pins Debugging for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A) + * Pins Debugging for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A) + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) */ #warning "PINS_DEBUGGING is not fully supported for Teensy 4.0 / 4.1 so 'M43' may cause hangs." #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin -#define PRINT_PORT(p) -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) -#define GET_ARRAY_PIN(p) pin_array[p].pin -#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital -#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0) -#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0)) -#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(13)) || ((P) >= analogInputToDigitalPin(14) && (P) <= analogInputToDigitalPin(17)) -#define pwm_status(pin) HAL_pwm_status(pin) -#define GET_PINMODE(PIN) (VALID_PIN(pin) && IS_OUTPUT(pin)) +#define getPinByIndex(x) pin_array[x].pin +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0)) +#define getValidPinMode(P) (isValidPin(P) && IS_OUTPUT(P)) +#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL)) +#define isAnalogPin(P) (pin_t(P) >= analogInputToDigitalPin(0) && pin_t(P) <= analogInputToDigitalPin(13)) || (pin_t(P) >= analogInputToDigitalPin(14) && pin_t(P) <= analogInputToDigitalPin(17)) +#define digitalRead_mod(P) extDigitalRead(P) // AVR digitalRead disabled PWM before it read the pin +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin struct pwm_pin_info_struct { @@ -120,12 +134,12 @@ const struct pwm_pin_info_struct pwm_pin_info[] = { #endif }; -void HAL_print_analog_pin(char buffer[], int8_t pin) { +void printAnalogPin(char buffer[], const pin_t pin) { if (pin <= 23) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 14)); else if (pin <= 41) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 24)); } -void HAL_analog_pin_state(char buffer[], int8_t pin) { +void analog_pin_state(char buffer[], const pin_t pin) { if (pin <= 23) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 14)); else if (pin <= 41) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 24)); } @@ -136,14 +150,14 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) { * Print a pin's PWM status. * Return true if it's currently a PWM pin. */ -bool HAL_pwm_status(int8_t pin) { +bool pwm_status(const pin_t pin) { char buffer[20]; // for the sprintf statements const struct pwm_pin_info_struct *info; - if (pin >= CORE_NUM_DIGITAL) return 0; - info = pwm_pin_info + pin; + if (pin >= CORE_NUM_DIGITAL) return false; - if (info->type == 0) return 0; + info = pwm_pin_info + pin; + if (info->type == 0) return false; /* TODO decode pwm value from timers */ // for now just indicate if output is set as pwm @@ -151,4 +165,6 @@ bool HAL_pwm_status(int8_t pin) { return (*(portConfigRegister(pin)) == info->muxval); } -static void pwm_details(uint8_t pin) { /* TODO */ } +void printPinPWM(const pin_t) { /* TODO */ } + +void printPinPort(const pin_t) {} diff --git a/Marlin/src/HAL/TEENSY40_41/spi_pins.h b/Marlin/src/HAL/TEENSY40_41/spi_pins.h index ba4a2c700a..fc1c2a7fed 100644 --- a/Marlin/src/HAL/TEENSY40_41/spi_pins.h +++ b/Marlin/src/HAL/TEENSY40_41/spi_pins.h @@ -28,4 +28,3 @@ #define SD_SCK_PIN 13 #define SD_MISO_PIN 12 #define SD_MOSI_PIN 11 -#define SD_SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 diff --git a/Marlin/src/HAL/TEENSY40_41/timers.cpp b/Marlin/src/HAL/TEENSY40_41/timers.cpp index ed99f65d6e..011f9fe31c 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.cpp +++ b/Marlin/src/HAL/TEENSY40_41/timers.cpp @@ -30,41 +30,82 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { switch (timer_num) { + + // + // Step Timer – GPT1 - Compare Interrupt OCR1 - Reset Mode + // case MF_TIMER_STEP: - CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode + // 24MHz mode off – Use peripheral clock (150MHz) + CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; + // Enable GPT1 clock gating CCM_CCGR1 |= CCM_CCGR1_GPT1_BUS(CCM_CCGR_ON); - GPT1_CR = 0; // disable timer - GPT1_SR = 0x3F; // clear all prior status - GPT1_PR = GPT1_TIMER_PRESCALE - 1; - GPT1_CR |= GPT_CR_CLKSRC(1); //clock selection #1 (peripheral clock = 150 MHz) - GPT1_CR |= GPT_CR_ENMOD; //reset count to zero before enabling - GPT1_CR |= GPT_CR_OM1(1); // toggle mode - GPT1_OCR1 = (GPT1_TIMER_RATE / frequency) -1; // Initial compare value - GPT1_IR = GPT_IR_OF1IE; // Compare3 value - GPT1_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz + // Disable timer, clear all status bits + GPT1_CR = 0; // Disable timer + GPT1_SR = 0x3F; // Clear all prior status - OUT_WRITE(15, HIGH); + // Prescaler = 2 => 75MHz counting clock + GPT1_PR = GPT1_TIMER_PRESCALE - 1; + + GPT1_CR = GPT_CR_CLKSRC(1) // Clock selection #1 (peripheral clock = 150 MHz) + | GPT_CR_ENMOD // Reset count to zero before enabling + | GPT_CR_OM2(TERN(MARLIN_DEV_MODE, 1, 0)); // 0 = edge compare, 1 = toggle + + // Compare value – the number of clocks between edges + GPT1_OCR1 = (GPT1_TIMER_RATE / frequency) - 1; + + // Enable compare‑event interrupt + GPT1_IR = GPT_IR_OF1IE; // OF1 interrupt enabled + + // Pull Pin 15 HIGH (logic‑high is the “idle†state) + TERN_(MARLIN_DEV_MODE, OUT_WRITE(15, HIGH)); + + // Attach and enable Stepper IRQ + // Note: UART priority is 16 attachInterruptVector(IRQ_GPT1, &stepTC_Handler); - NVIC_SET_PRIORITY(IRQ_GPT1, 16); + NVIC_SET_PRIORITY(IRQ_GPT1, 16); // Priority 16 (higher than Temp Timer) + + // Start GPT1 counting at 150 MHz + GPT1_CR |= GPT_CR_EN; + break; + + // + // Temperature Timer – GPT2 - Compare Interrupt OCR1 - Reset Mode + // case MF_TIMER_TEMP: - CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode + // 24MHz mode off – Use peripheral clock (150MHz) + CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; + // Enable GPT2 clock gating CCM_CCGR0 |= CCM_CCGR0_GPT2_BUS(CCM_CCGR_ON); - GPT2_CR = 0; // disable timer - GPT2_SR = 0x3F; // clear all prior status - GPT2_PR = GPT2_TIMER_PRESCALE - 1; - GPT2_CR |= GPT_CR_CLKSRC(1); //clock selection #1 (peripheral clock = 150 MHz) - GPT2_CR |= GPT_CR_ENMOD; //reset count to zero before enabling - GPT2_CR |= GPT_CR_OM1(1); // toggle mode - GPT2_OCR1 = (GPT2_TIMER_RATE / frequency) -1; // Initial compare value - GPT2_IR = GPT_IR_OF1IE; // Compare3 value - GPT2_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz + // Disable timer, clear all status bits + GPT2_CR = 0; // Disable timer + GPT2_SR = 0x3F; // Clear all prior status - OUT_WRITE(14, HIGH); + // Prescaler = 10 => 15MHz counting clock + GPT2_PR = GPT2_TIMER_PRESCALE - 1; + + GPT2_CR = GPT_CR_CLKSRC(1) // Clock selection #1 (peripheral clock = 150 MHz) + | GPT_CR_ENMOD // and reset count to zero before enabling + | GPT_CR_OM2(TERN(MARLIN_DEV_MODE, 1, 0)); // 0 = edge compare, 1 = toggle + + // Compare value – the number of clocks between edges + GPT2_OCR1 = (GPT2_TIMER_RATE / frequency) - 1; + + // Enable compare‑event interrupt + GPT2_IR = GPT_IR_OF1IE; // OF1 interrupt enabled + + // Pull Pin 14 HIGH (logic‑high is the “idle†state) + TERN_(MARLIN_DEV_MODE, OUT_WRITE(14, HIGH)); + + // Attach Temperature ISR attachInterruptVector(IRQ_GPT2, &tempTC_Handler); - NVIC_SET_PRIORITY(IRQ_GPT2, 32); + NVIC_SET_PRIORITY(IRQ_GPT2, 32); // Priority 32 (lower than Step Timer) + + // Start GPT2 counting at 150 MHz + GPT2_CR |= GPT_CR_EN; + break; } } @@ -82,6 +123,7 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) { case MF_TIMER_TEMP: NVIC_DISABLE_IRQ(IRQ_GPT2); break; } + // Ensure the CPU actually stops servicing the IRQ // We NEED memory barriers to ensure Interrupts are actually disabled! // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) asm volatile("dsb"); @@ -97,8 +139,8 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { void HAL_timer_isr_prologue(const uint8_t timer_num) { switch (timer_num) { - case MF_TIMER_STEP: GPT1_SR = GPT_IR_OF1IE; break; // clear OF3 bit - case MF_TIMER_TEMP: GPT2_SR = GPT_IR_OF1IE; break; // clear OF3 bit + case MF_TIMER_STEP: GPT1_SR = GPT_IR_OF1IE; break; // clear OF1 + case MF_TIMER_TEMP: GPT2_SR = GPT_IR_OF1IE; break; } asm volatile("dsb"); } diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 77fe0953d3..66d00b1788 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -33,15 +34,15 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFE +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX-1UL) -#define GPT_TIMER_RATE F_BUS_ACTUAL // 150MHz +#define GPT_TIMER_RATE (F_CPU / 4) // 150MHz (Can't use F_BUS_ACTUAL because it's extern volatile) #define GPT1_TIMER_PRESCALE 2 #define GPT2_TIMER_PRESCALE 10 -#define GPT1_TIMER_RATE (GPT_TIMER_RATE / GPT1_TIMER_PRESCALE) // 75MHz -#define GPT2_TIMER_RATE (GPT_TIMER_RATE / GPT2_TIMER_PRESCALE) // 15MHz +#define GPT1_TIMER_RATE (GPT_TIMER_RATE / GPT1_TIMER_PRESCALE) // 150MHz / 2 = 75MHz +#define GPT2_TIMER_RATE (GPT_TIMER_RATE / GPT2_TIMER_PRESCALE) // 150MHz / 10 = 15MHz #ifndef MF_TIMER_STEP #define MF_TIMER_STEP 0 // Timer Index for Stepper @@ -56,19 +57,19 @@ typedef uint32_t hal_timer_t; #define TEMP_TIMER_RATE 1000000 #define TEMP_TIMER_FREQUENCY 1000 -#define STEPPER_TIMER_RATE GPT1_TIMER_RATE -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) -#define STEPPER_TIMER_PRESCALE ((GPT_TIMER_RATE / 1000000) / STEPPER_TIMER_TICKS_PER_US) +#define HAL_TIMER_RATE GPT1_TIMER_RATE +#define STEPPER_TIMER_RATE HAL_TIMER_RATE +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) +#define STEPPER_TIMER_PRESCALE (GPT_TIMER_RATE / STEPPER_TIMER_RATE) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR @@ -87,8 +88,16 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { switch (timer_num) { - case MF_TIMER_STEP: GPT1_OCR1 = compare - 1; break; - case MF_TIMER_TEMP: GPT2_OCR1 = compare - 1; break; + case MF_TIMER_STEP: + GPT1_CR |= GPT_CR_FRR; // Free Run Mode (setting OCRx preserves CNT) + GPT1_OCR1 = compare - 1; + GPT1_CR &= ~GPT_CR_FRR; // Reset Mode (CNT resets on trigger) + break; + case MF_TIMER_TEMP: + GPT2_CR |= GPT_CR_FRR; // Free Run Mode (setting OCRx preserves CNT) + GPT2_OCR1 = compare - 1; + GPT2_CR &= ~GPT_CR_FRR; // Reset Mode (CNT resets on trigger) + break; } } @@ -113,5 +122,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -//void HAL_timer_isr_epilogue(const uint8_t timer_num) {} -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/TEENSY40_41/u8g/LCD_defines.h b/Marlin/src/HAL/TEENSY40_41/u8g/LCD_defines.h new file mode 100644 index 0000000000..349f8c0399 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/u8g/LCD_defines.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Teensy 4.0/4.1 LCD-specific defines + */ diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h index 28fe28e109..e7eea44308 100644 --- a/Marlin/src/HAL/platforms.h +++ b/Marlin/src/HAL/platforms.h @@ -24,32 +24,40 @@ #define XSTR(V...) #V #ifdef __AVR__ - #define HAL_PATH(PATH, NAME) XSTR(PATH/AVR/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/AVR/NAME) #elif defined(ARDUINO_ARCH_SAM) - #define HAL_PATH(PATH, NAME) XSTR(PATH/DUE/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/DUE/NAME) #elif defined(__MK20DX256__) - #define HAL_PATH(PATH, NAME) XSTR(PATH/TEENSY31_32/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/TEENSY31_32/NAME) #elif defined(__MK64FX512__) || defined(__MK66FX1M0__) - #define HAL_PATH(PATH, NAME) XSTR(PATH/TEENSY35_36/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/TEENSY35_36/NAME) #elif defined(__IMXRT1062__) - #define HAL_PATH(PATH, NAME) XSTR(PATH/TEENSY40_41/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/TEENSY40_41/NAME) #elif defined(TARGET_LPC1768) - #define HAL_PATH(PATH, NAME) XSTR(PATH/LPC1768/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/LPC1768/NAME) +#elif defined(ARDUINO_ARCH_HC32) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/HC32/NAME) +#elif defined(ARDUINO_ARCH_MFL) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/GD32_MFL/NAME) #elif defined(__STM32F1__) || defined(TARGET_STM32F1) - #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32F1/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/STM32F1/NAME) #elif defined(ARDUINO_ARCH_STM32) #ifndef HAL_STM32 #define HAL_STM32 #endif - #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/STM32/NAME) #elif defined(ARDUINO_ARCH_ESP32) - #define HAL_PATH(PATH, NAME) XSTR(PATH/ESP32/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/ESP32/NAME) #elif defined(__PLAT_LINUX__) - #define HAL_PATH(PATH, NAME) XSTR(PATH/LINUX/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/LINUX/NAME) #elif defined(__PLAT_NATIVE_SIM__) - #define HAL_PATH(PATH, NAME) XSTR(PATH/NATIVE_SIM/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/NATIVE_SIM/NAME) #elif defined(__SAMD51__) - #define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD51/NAME) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/SAMD51/NAME) +#elif defined(__SAMD21__) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/SAMD21/NAME) +#elif defined(__PLAT_RP2040__) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/RP2040/NAME) #else #error "Unsupported Platform!" #endif diff --git a/Marlin/src/HAL/shared/Delay.cpp b/Marlin/src/HAL/shared/Delay.cpp index c64376d25d..5aa3a235fd 100644 --- a/Marlin/src/HAL/shared/Delay.cpp +++ b/Marlin/src/HAL/shared/Delay.cpp @@ -85,7 +85,7 @@ } else { // Enable DWT counter - // From https://stackoverflow.com/a/41188674/1469714 + // From https://stackoverflow.com/questions/36378280/stm32-how-to-enable-dwt-cycle-counter/41188674#41188674 HW_REG(_DEM_CR) = HW_REG(_DEM_CR) | 0x01000000; // Enable trace #if __CORTEX_M == 7 HW_REG(_LAR) = 0xC5ACCE55; // Unlock access to DWT registers, see https://developer.arm.com/documentation/ihi0029/e/ section B2.3.10 @@ -109,13 +109,7 @@ #if ENABLED(MARLIN_DEV_MODE) void dump_delay_accuracy_check() { auto report_call_time = [](FSTR_P const name, FSTR_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) { - SERIAL_ECHOPGM("Calling "); - SERIAL_ECHOF(name); - SERIAL_ECHOLNPGM(" for ", cycles); - SERIAL_ECHOF(unit); - SERIAL_ECHOLNPGM(" took: ", total); - SERIAL_CHAR(' '); - SERIAL_ECHOF(unit); + SERIAL_ECHOLN(F("Calling "), name, F(" for "), cycles, C(' '), unit, F(" took: "), total, C(' '), unit); if (do_flush) SERIAL_FLUSHTX(); }; @@ -167,7 +161,6 @@ } #endif // MARLIN_DEV_MODE - #else void calibrate_delay_loop() {} diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h index a6795a78ea..eeaf4c59fc 100644 --- a/Marlin/src/HAL/shared/Delay.h +++ b/Marlin/src/HAL/shared/Delay.h @@ -100,7 +100,7 @@ void calibrate_delay_loop(); // For delay in microseconds, no smart delay selection is required, directly call the delay function // Teensy compiler is too old and does not accept smart delay compile-time / run-time selection correctly - #define DELAY_US(x) DelayCycleFnc((x) * ((F_CPU) / 1000000UL)) + #define DELAY_US(x) DelayCycleFnc((unsigned long)(x) * ((F_CPU) / 1000000UL)) #elif defined(__AVR__) FORCE_INLINE static void __delay_up_to_3c(uint8_t cycles) { @@ -164,7 +164,7 @@ void calibrate_delay_loop(); } // Delay in microseconds - #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL)) + #define DELAY_US(x) DELAY_CYCLES((unsigned long)(x) * ((F_CPU) / 1000000UL)) #define DELAY_CYCLES_VAR DELAY_CYCLES @@ -173,7 +173,10 @@ void calibrate_delay_loop(); // DELAY_CYCLES specified inside platform // Delay in microseconds - #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL)) + #define DELAY_US(x) DELAY_CYCLES((unsigned long)(x) * ((F_CPU) / 1000000UL)) + + #define DELAY_CYCLES_VAR DELAY_CYCLES + #else #error "Unsupported MCU architecture" diff --git a/Marlin/src/HAL/shared/HAL_ST7920.h b/Marlin/src/HAL/shared/HAL_ST7920.h index 4e362f96ba..305736c3a5 100644 --- a/Marlin/src/HAL/shared/HAL_ST7920.h +++ b/Marlin/src/HAL/shared/HAL_ST7920.h @@ -27,7 +27,7 @@ * (bypassing U8G), it will allow the LIGHTWEIGHT_UI to operate. */ -#if BOTH(HAS_MARLINUI_U8GLIB, LIGHTWEIGHT_UI) +#if ALL(HAS_MARLINUI_U8GLIB, LIGHTWEIGHT_UI) void ST7920_cs(); void ST7920_ncs(); void ST7920_set_cmd(); diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.cpp b/Marlin/src/HAL/shared/backtrace/unwarm.cpp index adbcca69cc..823f54c157 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarm.cpp @@ -33,8 +33,9 @@ void UnwPrintf(const char *format, ...) { va_list args; - va_start( args, format ); - vprintf(format, args ); + va_start(args, format); + vprintf(format, args); + va_end(args); } #endif @@ -49,7 +50,6 @@ void UnwInvalidateRegisterFile(RegData *regFile) { } while (t < 13); } - /** * Initialize the data used for unwinding. */ @@ -128,7 +128,6 @@ bool UnwReportRetAddr(UnwState * const state, uint32_t addr) { return state->cb->report((void *)state->reportData, &entry); } - /** * Write some register to memory. * This will store some register and meta data onto the virtual stack. diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.h b/Marlin/src/HAL/shared/backtrace/unwarm.h index edae90650e..8e432ebe77 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.h +++ b/Marlin/src/HAL/shared/backtrace/unwarm.h @@ -15,7 +15,7 @@ #include "unwinder.h" -/** The maximum number of instructions to interpet in a function. +/** The maximum number of instructions to interpret in a function. * Unwinding will be unconditionally stopped and UNWIND_EXHAUSTED returned * if more than this number of instructions are interpreted in a single * function without unwinding a stack frame. This prevents infinite loops @@ -41,7 +41,6 @@ typedef enum { REG_VAL_ARITHMETIC = 0x80 } RegValOrigin; - /** Type for tracking information about a register. * This stores the register value, as well as other data that helps unwinding. */ @@ -56,7 +55,6 @@ typedef struct { int o; /* (RegValOrigin) */ } RegData; - /** Structure used to track reads and writes to memory. * This structure is used as a hash to store a small number of writes * to memory. @@ -81,7 +79,6 @@ typedef struct { uint8_t tracked[(MEM_HASH_SIZE + 7) / 8]; } MemData; - /** Structure that is used to keep track of unwinding meta-data. * This data is passed between all the unwinding functions. */ diff --git a/Marlin/src/HAL/shared/backtrace/unwarm_arm.cpp b/Marlin/src/HAL/shared/backtrace/unwarm_arm.cpp index decf74e6e9..e6064f65da 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm_arm.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarm_arm.cpp @@ -414,7 +414,7 @@ UnwResult UnwStartArm(UnwState * const state) { /* S indicates that banked registers (untracked) are used, unless * this is a load including the PC when the S-bit indicates that - * that CPSR is loaded from SPSR (also untracked, but ignored). + * CPSR is loaded from SPSR (also untracked, but ignored). */ if (S && (!L || (regList & (0x01 << 15)) == 0)) { UnwPrintd1("\nError:S-bit set requiring banked registers\n"); @@ -431,7 +431,7 @@ UnwResult UnwStartArm(UnwState * const state) { /* Check if ascending or descending. * Registers are loaded/stored in order of address. - * i.e. r0 is at the lowest address, r15 at the highest. + * i.e., r0 is at the lowest address, r15 at the highest. */ r = U ? 0 : 15; do { diff --git a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp index 148927a19f..bd87b6731c 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp @@ -55,7 +55,12 @@ static const char *UnwTabGetFunctionName(const UnwindCallbacks *cb, uint32_t add return nullptr; if ((flag_word & 0xFF000000) == 0xFF000000) { - return (const char *)(address - 4 - (flag_word & 0x00FFFFFF)); + const uint32_t fn_name_addr = address - 4 - (flag_word & 0x00FFFFFF); + + // Ensure the address is readable to avoid returning a bogus pointer + uint8_t dummy = 0; + if (cb->readB(fn_name_addr, &dummy)) + return (const char *)fn_name_addr; } return nullptr; } diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp index a4151b38c2..da1cff4fcc 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp @@ -135,7 +135,7 @@ // Generic ARM code, that's testing if an access to the given address would cause a fault or not // It can't guarantee an address is in RAM or Flash only, but we usually don't care - #define NVIC_FAULT_STAT 0xE000ED28 // Configurable Fault Status Reg. + #define NVIC_FAULT_STAT 0xE000ED28 // Configurable Fault Status reg. #define NVIC_CFG_CTRL 0xE000ED14 // Configuration Control Register #define NVIC_FAULT_STAT_BFARV 0x00008000 // BFAR is valid #define NVIC_CFG_CTRL_BFHFNMIGN 0x00000100 // Ignore bus fault in NMI/fault diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index e54661c770..43a086589b 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2020 Cyril Russo * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,7 +26,6 @@ #if defined(__arm__) || defined(__thumb__) - /* On ARM CPUs exception handling is quite powerful. @@ -68,7 +66,7 @@ void * hook_get_usagefault_vector_address(unsigned vtor) { return (void*)(vtor + void * hook_get_reserved_vector_address(unsigned vtor) { return (void*)(vtor + 0x07); } // Common exception frame for ARM, should work for all ARM CPU -// Described here (modified for convenience): https://interrupt.memfault.com/blog/cortex-m-fault-debug +// Described here (modified for convenience): https://interrupt.memfault.com/blog/cortex-m-hardfault-debug struct __attribute__((packed)) ContextStateFrame { uint32_t r0; uint32_t r1; @@ -279,8 +277,6 @@ void CommonHandler_C(ContextStateFrame * frame, unsigned long lr, unsigned long if (!faulted_from_exception) { // Not sure about the non_usage_fault, we want to try anyway, don't we ? && !non_usage_fault_occurred) // Try to resume to our handler here CFSR |= CFSR; // The ARM programmer manual says you must write to 1 all fault bits to clear them so this instruction is correct - // The frame will not be valid when returning anymore, let's clean it - savedFrame.CFSR = 0; frame->pc = (uint32_t)resume_from_fault; // Patch where to return to frame->lr = 0xDEADBEEF; // If our handler returns (it shouldn't), let's make it trigger an exception immediately diff --git a/Marlin/src/HAL/shared/eeprom_api.cpp b/Marlin/src/HAL/shared/eeprom_api.cpp index 47cfa5a2db..62a8f2afbc 100644 --- a/Marlin/src/HAL/shared/eeprom_api.cpp +++ b/Marlin/src/HAL/shared/eeprom_api.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -22,7 +21,7 @@ */ #include "../../inc/MarlinConfigPre.h" -#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +#if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) #include "eeprom_api.h" PersistentStore persistentStore; diff --git a/Marlin/src/HAL/shared/eeprom_api.h b/Marlin/src/HAL/shared/eeprom_api.h index cd744f82dc..33d80695db 100644 --- a/Marlin/src/HAL/shared/eeprom_api.h +++ b/Marlin/src/HAL/shared/eeprom_api.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,6 +26,19 @@ #include "../../libs/crc16.h" +// For testing. Define with -DEEPROM_EXCL_ZONE=916,926 in INI files. +//#define EEPROM_EXCL_ZONE 916,926 // Test a range +//#define EEPROM_EXCL_ZONE 333 // Test a single byte + +#ifdef EEPROM_EXCL_ZONE + static constexpr int eeprom_exclude_zone[] = { EEPROM_EXCL_ZONE }, + eeprom_exclude_size = eeprom_exclude_zone[COUNT(eeprom_exclude_zone) - 1] - eeprom_exclude_zone[0] + 1; + #define REAL_EEPROM_ADDR(A) (A < eeprom_exclude_zone[0] ? (A) : (A) + eeprom_exclude_size) +#else + #define REAL_EEPROM_ADDR(A) (A) + static constexpr int eeprom_exclude_size = 0; +#endif + class PersistentStore { public: diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h index e496de2a03..8b9791e1f8 100644 --- a/Marlin/src/HAL/shared/eeprom_if.h +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp index 6b559e234b..bba9c626a4 100644 --- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -33,13 +33,14 @@ #if ENABLED(SOFT_I2C_EEPROM) #include - SlowSoftWire Wire = SlowSoftWire(I2C_SDA_PIN, I2C_SCL_PIN, true); + SlowSoftWire eWire = SlowSoftWire(I2C_SDA_PIN, I2C_SCL_PIN, true); #else #include + #define eWire Wire #endif void eeprom_init() { - Wire.begin( + eWire.begin( #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN) #endif @@ -75,16 +76,16 @@ static uint8_t _eeprom_calc_device_address(uint8_t * const pos) { static void _eeprom_begin(uint8_t * const pos) { const unsigned eeprom_address = (unsigned)pos; - Wire.beginTransmission(_eeprom_calc_device_address(pos)); + eWire.beginTransmission(_eeprom_calc_device_address(pos)); if (!SMALL_EEPROM) - Wire.write(uint8_t((eeprom_address >> 8) & 0xFF)); // Address High, if needed - Wire.write(uint8_t(eeprom_address & 0xFF)); // Address Low + eWire.write(uint8_t((eeprom_address >> 8) & 0xFF)); // Address High, if needed + eWire.write(uint8_t(eeprom_address & 0xFF)); // Address Low } void eeprom_write_byte(uint8_t *pos, uint8_t value) { _eeprom_begin(pos); - Wire.write(value); - Wire.endTransmission(); + eWire.write(value); + eWire.endTransmission(); // wait for write cycle to complete // this could be done more efficiently with "acknowledge polling" @@ -93,9 +94,9 @@ void eeprom_write_byte(uint8_t *pos, uint8_t value) { uint8_t eeprom_read_byte(uint8_t *pos) { _eeprom_begin(pos); - Wire.endTransmission(); - Wire.requestFrom(_eeprom_calc_device_address(pos), (byte)1); - return Wire.available() ? Wire.read() : 0xFF; + eWire.endTransmission(); + eWire.requestFrom(_eeprom_calc_device_address(pos), (byte)1); + return eWire.available() ? eWire.read() : 0xFF; } #endif // USE_SHARED_EEPROM diff --git a/Marlin/src/HAL/shared/eeprom_if_spi.cpp b/Marlin/src/HAL/shared/eeprom_if_spi.cpp index 72c35addcb..6aa23e823a 100644 --- a/Marlin/src/HAL/shared/eeprom_if_spi.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_spi.cpp @@ -81,4 +81,4 @@ void eeprom_write_byte(uint8_t *pos, uint8_t value) { } #endif // USE_SHARED_EEPROM -#endif // I2C_EEPROM +#endif // SPI_EEPROM diff --git a/Marlin/src/HAL/shared/esp_wifi.cpp b/Marlin/src/HAL/shared/esp_wifi.cpp index a55f5ca39f..8a6ac2dfa9 100644 --- a/Marlin/src/HAL/shared/esp_wifi.cpp +++ b/Marlin/src/HAL/shared/esp_wifi.cpp @@ -21,6 +21,9 @@ */ #include "../../inc/MarlinConfig.h" + +#if ENABLED(WIFISUPPORT) + #include "Delay.h" void esp_wifi_init(void) { // init ESP01 WIFI module pins @@ -41,3 +44,5 @@ void esp_wifi_init(void) { // init ESP01 WIFI module pi OUT_WRITE(ESP_WIFI_MODULE_ENABLE_PIN, HIGH); #endif } + +#endif // WIFISUPPORT diff --git a/Marlin/src/HAL/shared/fauxpins.h b/Marlin/src/HAL/shared/fauxpins.h new file mode 100644 index 0000000000..924bfba02a --- /dev/null +++ b/Marlin/src/HAL/shared/fauxpins.h @@ -0,0 +1,367 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// +// Faux pins for Dependency Check +// + +// +// STM32 Pin Names +// +#define PA0 0x10 +#define PA1 0x11 +#define PA2 0x12 +#define PA3 0x13 +#define PA4 0x14 +#define PA5 0x15 +#define PA6 0x16 +#define PA7 0x17 +#define PA8 0x18 +#define PA9 0x19 +#define PA10 0x1A +#define PA11 0x1B +#define PA12 0x1C +#define PA13 0x1D +#define PA14 0x1E +#define PA15 0x1F + +#define PB0 0x20 +#define PB1 0x21 +#define PB2 0x22 +#define PB3 0x23 +#define PB4 0x24 +#define PB5 0x25 +#define PB6 0x26 +#define PB7 0x27 +#define PB8 0x28 +#define PB9 0x29 +#define PB10 0x2A +#define PB11 0x2B +#define PB12 0x2C +#define PB13 0x2D +#define PB14 0x2E +#define PB15 0x2F + +#define PC0 0x30 +#define PC1 0x31 +#define PC2 0x32 +#define PC3 0x33 +#define PC4 0x34 +#define PC5 0x35 +#define PC6 0x36 +#define PC7 0x37 +#define PC8 0x38 +#define PC9 0x39 +#define PC10 0x3A +#define PC11 0x3B +#define PC12 0x3C +#define PC13 0x3D +#define PC14 0x3E +#define PC15 0x3F + +#define PD0 0x40 +#define PD1 0x41 +#define PD2 0x42 +#define PD3 0x43 +#define PD4 0x44 +#define PD5 0x45 +#define PD6 0x46 +#define PD7 0x47 +#define PD8 0x48 +#define PD9 0x49 +#define PD10 0x4A +#define PD11 0x4B +#define PD12 0x4C +#define PD13 0x4D +#define PD14 0x4E +#define PD15 0x4F + +#define PE0 0x50 +#define PE1 0x51 +#define PE2 0x52 +#define PE3 0x53 +#define PE4 0x54 +#define PE5 0x55 +#define PE6 0x56 +#define PE7 0x57 +#define PE8 0x58 +#define PE9 0x59 +#define PE10 0x5A +#define PE11 0x5B +#define PE12 0x5C +#define PE13 0x5D +#define PE14 0x5E +#define PE15 0x5F + +#define PF0 0x60 +#define PF1 0x61 +#define PF2 0x62 +#define PF3 0x63 +#define PF4 0x64 +#define PF5 0x65 +#define PF6 0x66 +#define PF7 0x67 +#define PF8 0x68 +#define PF9 0x69 +#define PF10 0x6A +#define PF11 0x6B +#define PF12 0x6C +#define PF13 0x6D +#define PF14 0x6E +#define PF15 0x6F + +#define PG0 0x70 +#define PG1 0x71 +#define PG2 0x72 +#define PG3 0x73 +#define PG4 0x74 +#define PG5 0x75 +#define PG6 0x76 +#define PG7 0x77 +#define PG8 0x78 +#define PG9 0x79 +#define PG10 0x7A +#define PG11 0x7B +#define PG12 0x7C +#define PG13 0x7D +#define PG14 0x7E +#define PG15 0x7F + +#define PH0 0x80 +#define PH1 0x81 +#define PH2 0x82 +#define PH3 0x83 +#define PH4 0x84 +#define PH5 0x85 +#define PH6 0x86 +#define PH7 0x87 +#define PH8 0x88 +#define PH9 0x89 +#define PH10 0x8A +#define PH11 0x8B +#define PH12 0x8C +#define PH13 0x8D +#define PH14 0x8E +#define PH15 0x8F + +#define PI0 0x90 +#define PI1 0x91 +#define PI2 0x92 +#define PI3 0x93 +#define PI4 0x94 +#define PI5 0x95 +#define PI6 0x96 +#define PI7 0x97 +#define PI8 0x98 +#define PI9 0x99 +#define PI10 0x9A +#define PI11 0x9B +#define PI12 0x9C +#define PI13 0x9D +#define PI14 0x9E +#define PI15 0x9F + +#define PJ0 0xA0 +#define PJ1 0xA1 +#define PJ2 0xA2 +#define PJ3 0xA3 +#define PJ4 0xA4 +#define PJ5 0xA5 +#define PJ6 0xA6 +#define PJ7 0xA7 +#define PJ8 0xA8 +#define PJ9 0xA9 +#define PJ10 0xAA +#define PJ11 0xAB +#define PJ12 0xAC +#define PJ13 0xAD +#define PJ14 0xAE +#define PJ15 0xAF + +// +// LPC Pin Names +// +#define P0_00 100 +#define P0_01 101 +#define P0_02 102 +#define P0_03 103 +#define P0_04 104 +#define P0_05 105 +#define P0_06 106 +#define P0_07 107 +#define P0_08 108 +#define P0_09 109 +#define P0_10 110 +#define P0_11 111 +#define P0_12 112 +#define P0_13 113 +#define P0_14 114 +#define P0_15 115 +#define P0_16 116 +#define P0_17 117 +#define P0_18 118 +#define P0_19 119 +#define P0_20 120 +#define P0_21 121 +#define P0_22 122 +#define P0_23 123 +#define P0_24 124 +#define P0_25 125 +#define P0_26 126 +#define P0_27 127 +#define P0_28 128 +#define P0_29 129 +#define P0_30 130 +#define P0_31 131 + +#define P1_00 200 +#define P1_01 201 +#define P1_02 202 +#define P1_03 203 +#define P1_04 204 +#define P1_05 205 +#define P1_06 206 +#define P1_07 207 +#define P1_08 208 +#define P1_09 209 +#define P1_10 210 +#define P1_11 211 +#define P1_12 212 +#define P1_13 213 +#define P1_14 214 +#define P1_15 215 +#define P1_16 216 +#define P1_17 217 +#define P1_18 218 +#define P1_19 219 +#define P1_20 220 +#define P1_21 221 +#define P1_22 222 +#define P1_23 223 +#define P1_24 224 +#define P1_25 225 +#define P1_26 226 +#define P1_27 227 +#define P1_28 228 +#define P1_29 229 +#define P1_30 230 +#define P1_31 231 + +#define P2_00 300 +#define P2_01 301 +#define P2_02 302 +#define P2_03 303 +#define P2_04 304 +#define P2_05 305 +#define P2_06 306 +#define P2_07 307 +#define P2_08 308 +#define P2_09 309 +#define P2_10 310 +#define P2_11 311 +#define P2_12 312 +#define P2_13 313 +#define P2_14 314 +#define P2_15 315 +#define P2_16 316 +#define P2_17 317 +#define P2_18 318 +#define P2_19 319 +#define P2_20 320 +#define P2_21 321 +#define P2_22 322 +#define P2_23 323 +#define P2_24 324 +#define P2_25 325 +#define P2_26 326 +#define P2_27 327 +#define P2_28 328 +#define P2_29 329 +#define P2_30 330 +#define P2_31 331 + +#define P3_00 400 +#define P3_01 401 +#define P3_02 402 +#define P3_03 403 +#define P3_04 404 +#define P3_05 405 +#define P3_06 406 +#define P3_07 407 +#define P3_08 408 +#define P3_09 409 +#define P3_10 410 +#define P3_11 411 +#define P3_12 412 +#define P3_13 413 +#define P3_14 414 +#define P3_15 415 +#define P3_16 416 +#define P3_17 417 +#define P3_18 418 +#define P3_19 419 +#define P3_20 420 +#define P3_21 421 +#define P3_22 422 +#define P3_23 423 +#define P3_24 424 +#define P3_25 425 +#define P3_26 426 +#define P3_27 427 +#define P3_28 428 +#define P3_29 429 +#define P3_30 430 +#define P3_31 431 + +#define P4_00 500 +#define P4_01 501 +#define P4_02 502 +#define P4_03 503 +#define P4_04 504 +#define P4_05 505 +#define P4_06 506 +#define P4_07 507 +#define P4_08 508 +#define P4_09 509 +#define P4_10 510 +#define P4_11 511 +#define P4_12 512 +#define P4_13 513 +#define P4_14 514 +#define P4_15 515 +#define P4_16 516 +#define P4_17 517 +#define P4_18 518 +#define P4_19 519 +#define P4_20 520 +#define P4_21 521 +#define P4_22 522 +#define P4_23 523 +#define P4_24 524 +#define P4_25 525 +#define P4_26 526 +#define P4_27 527 +#define P4_28 528 +#define P4_29 529 +#define P4_30 530 +#define P4_31 531 diff --git a/Marlin/src/HAL/shared/math_32bit.h b/Marlin/src/HAL/shared/math_32bit.h index 1fb233e3e8..daf82e0650 100644 --- a/Marlin/src/HAL/shared/math_32bit.h +++ b/Marlin/src/HAL/shared/math_32bit.h @@ -22,6 +22,7 @@ #pragma once #include "../../core/macros.h" +#include /** * Math helper functions for 32 bit CPUs diff --git a/Marlin/src/HAL/shared/progmem.h b/Marlin/src/HAL/shared/progmem.h index 4cd7663df9..b3bd5c32fd 100644 --- a/Marlin/src/HAL/shared/progmem.h +++ b/Marlin/src/HAL/shared/progmem.h @@ -39,7 +39,7 @@ #endif #ifndef F class __FlashStringHelper; -#define F(str) (reinterpret_cast(PSTR(str))) +#define F(string_literal) (reinterpret_cast(PSTR(string_literal))) #endif #ifndef _SFR_BYTE #define _SFR_BYTE(n) (n) diff --git a/Marlin/src/HAL/shared/serial_ports.h b/Marlin/src/HAL/shared/serial_ports.h new file mode 100644 index 0000000000..2daeea34e3 --- /dev/null +++ b/Marlin/src/HAL/shared/serial_ports.h @@ -0,0 +1,178 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * serial_ports.h - Define Marlin serial port macros and optionally declare ports + * + * This header defines one or more of the serial ports... + * - MYSERIAL1/2/3 ..... for host devices + * - MMU_SERIAL ........ for Multi-Material color changers + * - LCD_SERIAL ........ for serial LCDs + * - RS485_SERIAL ...... for CAN bus devices + * + * Before including this header define the following macros: + * - SERIAL_INDEX_MIN, SERIAL_INDEX_MAX to provide the valid range of serial port indexes. + * - _MSERIAL(X) and MSERIAL(X) to provide the instance name of Serial Port X. (Default: MSerial##X) + * - EP_SERIAL_PORT(X) to provide the instance name of Emergency Parser serial port X (if it is special). + * - USB_SERIAL_PORT(X) to provide the instance name of the USB serial port (if any). + * - ETH_SERIAL_PORT(X) to provide the instance name of the Ethernet serial port (if any). + * - DECLARE_SERIAL(X) to declare standard a serial port with the given index. + */ + +#ifndef _MSERIAL + #define _MSERIAL(X) MSerial##X +#endif +#ifndef MSERIAL + #define MSERIAL(X) _MSERIAL(X) +#endif + +#define INDEX_RANGE_MSG " must be from " STRINGIFY(SERIAL_INDEX_MIN) " to " STRINGIFY(SERIAL_INDEX_MAX) +#if defined(USB_SERIAL_PORT) && defined(ETH_SERIAL_PORT) + #define MORE_INDEXES_MSG ", -1 for Native USB, or -2 for Ethernet" +#elif defined(USB_SERIAL_PORT) + #define MORE_INDEXES_MSG ", or -1 for Native USB" +#elif defined(ETH_SERIAL_PORT) + #define MORE_INDEXES_MSG ", or -2 for Ethernet" +#else + #define MORE_INDEXES_MSG +#endif + +// +// SERIAL_PORT => MYSERIAL1 +// + +#if defined(EP_SERIAL_PORT) && ENABLED(EMERGENCY_PARSER) + #define MYSERIAL1 EP_SERIAL_PORT(1) +#elif WITHIN(SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) + #ifdef DECLARE_SERIAL + DECLARE_SERIAL(SERIAL_PORT); + #endif +#elif SERIAL_PORT == -1 && defined(USB_SERIAL_PORT) + #define MYSERIAL1 USB_SERIAL_PORT(1) +#elif SERIAL_PORT == -2 && defined(ETH_SERIAL_PORT) + #define MYSERIAL1 ETH_SERIAL_PORT(1) +#endif +#ifndef MYSERIAL1 + static_assert(false, "SERIAL_PORT" INDEX_RANGE_MSG MORE_INDEXES_MSG "."); + #define MYSERIAL1 _MSERIAL(1) // Dummy port +#endif + +// +// SERIAL_PORT_2 => MYSERIAL2 +// + +#ifdef SERIAL_PORT_2 + #if defined(EP_SERIAL_PORT) && ENABLED(EMERGENCY_PARSER) + #define MYSERIAL2 EP_SERIAL_PORT(2) + #elif WITHIN(SERIAL_PORT_2, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) + #ifdef DECLARE_SERIAL + DECLARE_SERIAL(SERIAL_PORT_2); + #endif + #elif SERIAL_PORT_2 == -1 && defined(USB_SERIAL_PORT) + #define MYSERIAL2 USB_SERIAL_PORT(2) + #elif SERIAL_PORT_2 == -2 && defined(ETH_SERIAL_PORT) + #define MYSERIAL2 ETH_SERIAL_PORT(2) + #endif + #ifndef MYSERIAL2 + static_assert(false, "SERIAL_PORT_2" INDEX_RANGE_MSG MORE_INDEXES_MSG "."); + #define MYSERIAL2 _MSERIAL(1) // Dummy port + #endif +#endif + +// +// SERIAL_PORT_3 => MYSERIAL3 +// + +#ifdef SERIAL_PORT_3 + #if defined(EP_SERIAL_PORT) && ENABLED(EMERGENCY_PARSER) + #define MYSERIAL3 EP_SERIAL_PORT(3) + #elif WITHIN(SERIAL_PORT_3, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #ifdef DECLARE_SERIAL + DECLARE_SERIAL(SERIAL_PORT_3); + #endif + #elif SERIAL_PORT_3 == -1 && defined(USB_SERIAL_PORT) + #define MYSERIAL3 USB_SERIAL_PORT(3) + #elif SERIAL_PORT_3 == -2 && defined(ETH_SERIAL_PORT) + #define MYSERIAL3 ETH_SERIAL_PORT(3) + #endif + #ifndef MYSERIAL3 + static_assert(false, "SERIAL_PORT_3" INDEX_RANGE_MSG MORE_INDEXES_MSG "."); + #define MYSERIAL3 _MSERIAL(1) // Dummy port + #endif +#endif + +// +// MMU_SERIAL_PORT => MMU_SERIAL +// + +#ifdef MMU_SERIAL_PORT + #if WITHIN(MMU_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + #define MMU_SERIAL MSERIAL(MMU_SERIAL_PORT) + #ifdef DECLARE_SERIAL + DECLARE_SERIAL(MMU_SERIAL_PORT); + #endif + #else + static_assert(false, "MMU_SERIAL_PORT" INDEX_RANGE_MSG "."); + #define MMU_SERIAL _MSERIAL(1) // Dummy port + #endif +#endif + +// +// LCD_SERIAL_PORT => LCD_SERIAL +// + +#ifdef LCD_SERIAL_PORT + #if WITHIN(LCD_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) + #ifdef DECLARE_SERIAL + DECLARE_SERIAL(LCD_SERIAL_PORT); + #endif + #else + static_assert(false, "LCD_SERIAL_PORT" INDEX_RANGE_MSG "."); + #define LCD_SERIAL _MSERIAL(1) // Dummy port + #endif +#endif + +// +// RS485_SERIAL_PORT => RS485_SERIAL +// + +#ifdef RS485_SERIAL_PORT + #if WITHIN(RS485_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX) + #define RS485_SERIAL MSERIAL(RS485_SERIAL_PORT) + #ifdef DECLARE_SERIAL + DECLARE_SERIAL(RS485_SERIAL_PORT); + #endif + #else + static_assert(false, "RS485_SERIAL_PORT" INDEX_RANGE_MSG "."); + #define RS485_SERIAL _MSERIAL(1) // Dummy port + #endif +#endif + +#undef DECLARE_SERIAL +#undef SERIAL_INDEX_MIN +#undef SERIAL_INDEX_MAX +#undef INDEX_RANGE_MSG diff --git a/Marlin/src/HAL/shared/servo.cpp b/Marlin/src/HAL/shared/servo.cpp index b838800de6..543bc8e873 100644 --- a/Marlin/src/HAL/shared/servo.cpp +++ b/Marlin/src/HAL/shared/servo.cpp @@ -60,14 +60,14 @@ ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures uint8_t ServoCount = 0; // the total number of attached servos -#define SERVO_MIN(v) (MIN_PULSE_WIDTH - (v) * 4) // minimum value in uS for this servo -#define SERVO_MAX(v) (MAX_PULSE_WIDTH - (v) * 4) // maximum value in uS for this servo +#define SERVO_MIN_US(v) (MIN_PULSE_WIDTH - (v) * 4) // minimum value in uS for this servo +#define SERVO_MAX_US(v) (MAX_PULSE_WIDTH - (v) * 4) // maximum value in uS for this servo /************ static functions common to all instances ***********************/ static bool anyTimerChannelActive(const timer16_Sequence_t timer) { // returns true if any servo is active on this timer - LOOP_L_N(channel, SERVOS_PER_TIMER) { + for (uint8_t channel = 0; channel < SERVOS_PER_TIMER; ++channel) { if (SERVO(timer, channel).Pin.isActive) return true; } @@ -117,7 +117,7 @@ void Servo::detach() { void Servo::write(int value) { if (value < MIN_PULSE_WIDTH) // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds) - value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(min), SERVO_MAX(max)); + value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN_US(min), SERVO_MAX_US(max)); writeMicroseconds(value); } @@ -126,8 +126,8 @@ void Servo::writeMicroseconds(int value) { byte channel = servoIndex; if (channel < MAX_SERVOS) { // ensure channel is valid // ensure pulse width is valid - value = constrain(value, SERVO_MIN(min), SERVO_MAX(max)) - (TRIM_DURATION); - value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009 + LIMIT(value, SERVO_MIN_US(min), SERVO_MAX_US(max)); + value = usToTicks(value - (TRIM_DURATION)); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009 CRITICAL_SECTION_START(); servo_info[channel].ticks = value; @@ -136,7 +136,7 @@ void Servo::writeMicroseconds(int value) { } // return the value as degrees -int Servo::read() { return map(readMicroseconds() + 1, SERVO_MIN(min), SERVO_MAX(max), 0, 180); } +int Servo::read() { return map(readMicroseconds() + 1, SERVO_MIN_US(min), SERVO_MAX_US(max), 0, 180); } int Servo::readMicroseconds() { return (servoIndex == INVALID_SERVO) ? 0 : ticksToUs(servo_info[servoIndex].ticks) + (TRIM_DURATION); diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h index c2560a8538..85e645146c 100644 --- a/Marlin/src/HAL/shared/servo.h +++ b/Marlin/src/HAL/shared/servo.h @@ -59,7 +59,7 @@ * write() - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds) * writeMicroseconds() - Sets the servo pulse width in microseconds * read() - Gets the last written servo pulse width as an angle between 0 and 180. - * readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release) + * readMicroseconds() - Gets the last written servo pulse width in microseconds. * attached() - Returns true if there is a servo attached. * detach() - Stops an attached servos from pulsing its i/o pin. * move(angle) - Sequence of attach(0), write(angle), @@ -74,19 +74,27 @@ #include "../TEENSY40_41/Servo.h" #elif defined(TARGET_LPC1768) #include "../LPC1768/Servo.h" +#elif defined(ARDUINO_ARCH_HC32) + #include "../HC32/Servo.h" +#elif defined(ARDUINO_ARCH_MFL) + #include "../GD32_MFL/Servo.h" #elif defined(__STM32F1__) || defined(TARGET_STM32F1) #include "../STM32F1/Servo.h" #elif defined(ARDUINO_ARCH_STM32) #include "../STM32/Servo.h" #elif defined(ARDUINO_ARCH_ESP32) #include "../ESP32/Servo.h" +#elif defined(__PLAT_RP2040__) + #include "../RP2040/Servo.h" +#elif defined(__PLAT_NATIVE_SIM__) + #include "../NATIVE_SIM/Servo.h" #else #include - #if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) + #if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) || defined(__SAMD21__) || defined(__PLAT_RP2040__) // we're good to go #else - #error "This library only supports boards with an AVR, SAM3X or SAMD51 processor." + #error "This library only supports boards with an AVR, SAM3X, SAMD21, SAMD51, or RP2040 processor." #endif #define Servo_VERSION 2 // software version of this library @@ -94,22 +102,22 @@ class Servo { public: Servo(); - int8_t attach(const int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail) - int8_t attach(const int pin, const int min, const int max); // as above but also sets min and max values for writes. + int8_t attach(const int pin); // Attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail) + int8_t attach(const int pin, const int min, const int max); // As above but also set min and max values for writes. void detach(); - void write(int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds - void writeMicroseconds(int value); // write pulse width in microseconds - void move(const int value); // attach the servo, then move to value - // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds - // if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach - int read(); // returns current pulse width as an angle between 0 and 180 degrees - int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release) - bool attached(); // return true if this servo is attached, otherwise false + void write(int value); // If value is < 200 it is treated as an angle, otherwise as pulse width in microseconds + void writeMicroseconds(int value); // Write pulse width in microseconds + void move(const int value); // Attach the servo, then move to value + // If value is < 200 it is treated as an angle, otherwise as pulse width in microseconds + // If DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach + int read(); // Return current pulse width as an angle between 0 and 180 degrees + int readMicroseconds(); // Return current pulse width in microseconds for this servo + bool attached(); // Return true if this servo is attached, otherwise false private: - uint8_t servoIndex; // index into the channel data for this servo - int8_t min; // minimum is this value times 4 added to MIN_PULSE_WIDTH - int8_t max; // maximum is this value times 4 added to MAX_PULSE_WIDTH + uint8_t servoIndex; // Index into the channel data for this servo + int8_t min; // Minimum is this value times 4 added to MIN_PULSE_WIDTH + int8_t max; // Maximum is this value times 4 added to MAX_PULSE_WIDTH }; #endif diff --git a/Marlin/src/HAL/shared/servo_private.h b/Marlin/src/HAL/shared/servo_private.h index 10cc5a1988..8fd5ab2d88 100644 --- a/Marlin/src/HAL/shared/servo_private.h +++ b/Marlin/src/HAL/shared/servo_private.h @@ -49,8 +49,10 @@ #include "../DUE/ServoTimers.h" #elif defined(__SAMD51__) #include "../SAMD51/ServoTimers.h" +#elif defined(__SAMD21__) + #include "../SAMD21/ServoTimers.h" #else - #error "This library only supports boards with an AVR, SAM3X or SAMD51 processor." + #error "This library only supports boards with an AVR, SAM3X, SAMD21 or SAMD51 processor." #endif // Macros diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 1e2e6c6483..6d672e3b8c 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -34,6 +34,10 @@ #include "HAL/shared/esp_wifi.h" #include "HAL/shared/cpu_exception/exception_hook.h" +#if ENABLED(WIFISUPPORT) + #include "HAL/shared/esp_wifi.h" +#endif + #ifdef ARDUINO #include #endif @@ -46,6 +50,9 @@ #include "module/settings.h" #include "module/stepper.h" #include "module/temperature.h" +#if ENABLED(FT_MOTION) + #include "module/ft_motion.h" +#endif #include "gcode/gcode.h" #include "gcode/parser.h" @@ -67,13 +74,13 @@ #endif #if HAS_DWIN_E3V2 - #include "lcd/e3v2/common/encoder.h" + #include "lcd/dwin/common/encoder.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "lcd/e3v2/creality/dwin.h" - #elif ENABLED(DWIN_LCD_PROUI) - #include "lcd/e3v2/proui/dwin.h" + #include "lcd/dwin/creality/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "lcd/e3v2/jyersui/dwin.h" + #include "lcd/dwin/jyersui/dwin.h" + #elif ENABLED(SOVOL_SV06_RTS) + #include "lcd/sovol_rts/sovol_rts.h" #endif #endif @@ -145,29 +152,22 @@ #include "feature/encoder_i2c.h" #endif -#if (HAS_TRINAMIC_CONFIG || HAS_TMC_SPI) && DISABLED(PSU_DEFAULT_OFF) - #include "feature/tmc_util.h" +#if HAS_TRINAMIC_CONFIG + #include "module/stepper/trinamic.h" #endif #if HAS_CUTTER #include "feature/spindle_laser.h" #endif -#if ENABLED(SDSUPPORT) - CardReader card; -#endif - -#if ENABLED(G38_PROBE_TARGET) - uint8_t G38_move; // = 0 - bool G38_did_trigger; // = false -#endif - #if ENABLED(DELTA) #include "module/delta.h" #elif ENABLED(POLARGRAPH) #include "module/polargraph.h" #elif IS_SCARA #include "module/scara.h" +#elif ENABLED(POLAR) + #include "module/polar.h" #endif #if HAS_LEVELING @@ -190,7 +190,7 @@ #include "feature/runout.h" #endif -#if EITHER(PROBE_TARE, HAS_Z_SERVO_PROBE) +#if ANY(PROBE_TARE, HAS_Z_SERVO_PROBE) #include "module/probe.h" #endif @@ -210,7 +210,9 @@ #include "feature/fanmux.h" #endif -#include "module/tool_change.h" +#if HAS_TOOLCHANGE + #include "module/tool_change.h" +#endif #if HAS_FANCHECK #include "feature/fancheck.h" @@ -220,19 +222,21 @@ #include "feature/controllerfan.h" #endif -#if HAS_PRUSA_MMU1 - #include "feature/mmu/mmu.h" -#endif - -#if HAS_PRUSA_MMU2 +#if HAS_PRUSA_MMU3 + #include "feature/mmu3/mmu3.h" + #include "feature/mmu3/mmu3_reporting.h" + #include "feature/mmu3/SpoolJoin.h" +#elif HAS_PRUSA_MMU2 #include "feature/mmu/mmu2.h" +#elif HAS_PRUSA_MMU1 + #include "feature/mmu/mmu.h" #endif #if ENABLED(PASSWORD_FEATURE) #include "feature/password/password.h" #endif -#if ENABLED(DGUS_LCD_UI_MKS) +#if DGUS_LCD_UI_MKS #include "lcd/extui/dgus/DGUSScreenHandler.h" #endif @@ -252,25 +256,55 @@ #include "tests/marlin_tests.h" #endif -PGMSTR(M112_KILL_STR, "M112 Shutdown"); +#if HAS_RS485_SERIAL + #include "feature/rs485.h" +#endif -MarlinState marlin_state = MF_INITIALIZING; +/** + * Spin in place here while keeping temperature processing alive + */ +void safe_delay(millis_t ms) { + while (ms > 50) { + ms -= 50; + delay(50); + thermalManager.task(); + } + delay(ms); + thermalManager.task(); // This keeps us safe if too many small safe_delay() calls are made +} + +// Singleton for Marlin global data and methods +Marlin marlin; + +// Marlin static data +#if ENABLED(CONFIGURABLE_MACHINE_NAME) + MString<64> Marlin::machine_name; +#endif + +// Global state of the firmware +MarlinState Marlin::state = MF_INITIALIZING; // For M109 and M190, this flag may be cleared (by M108) to exit the wait loop -bool wait_for_heatup = true; +bool Marlin::wait_for_heatup = false; + +#if !HAS_MEDIA + CardReader card; // Stub instance with "no media" methods +#endif + +PGMSTR(M112_KILL_STR, "M112 Shutdown"); // For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop #if HAS_RESUME_CONTINUE - bool wait_for_user; // = false; + bool Marlin::wait_for_user; // = false - void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) { + void Marlin::wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) { UNUSED(no_sleep); KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; + wait_start(); if (ms) ms += millis(); // expire time while (wait_for_user && !(ms && ELAPSED(millis(), ms))) idle(TERN_(ADVANCED_PAUSE_FEATURE, no_sleep)); - wait_for_user = false; + user_resume(); while (ui.button_pressed()) safe_delay(50); } @@ -298,63 +332,52 @@ bool wait_for_heatup = true; #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wnarrowing" +#pragma GCC diagnostic ignored "-Wsign-compare" -#ifndef RUNTIME_ONLY_ANALOG_TO_DIGITAL - template - constexpr pin_t OnlyPins<_SP_END, D...>::table[sizeof...(D)]; -#endif - -bool pin_is_protected(const pin_t pin) { - #ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL - static const pin_t sensitive_pins[] PROGMEM = { SENSITIVE_PINS }; - const size_t pincount = COUNT(sensitive_pins); - #else - static constexpr size_t pincount = OnlyPins::size; - static const pin_t (&sensitive_pins)[pincount] PROGMEM = OnlyPins::table; - #endif - LOOP_L_N(i, pincount) { - const pin_t * const pptr = &sensitive_pins[i]; - if (pin == (sizeof(pin_t) == 2 ? (pin_t)pgm_read_word(pptr) : (pin_t)pgm_read_byte(pptr))) return true; - } +bool Marlin::pin_is_protected(const pin_t pin) { + #define pgm_read_pin(P) (sizeof(pin_t) == 2 ? (pin_t)pgm_read_word(P) : (pin_t)pgm_read_byte(P)) + for (uint8_t i = 0; i < COUNT(sensitive_dio); ++i) + if (pin == pgm_read_pin(&sensitive_dio[i])) return true; + for (uint8_t i = 0; i < COUNT(sensitive_aio); ++i) + if (pin == analogInputToDigitalPin(pgm_read_pin(&sensitive_aio[i]))) return true; return false; } #pragma GCC diagnostic pop -bool printer_busy() { - return planner.movesplanned() || printingIsActive(); +bool Marlin::printer_busy() { + return planner.has_blocks_queued() || printingIsActive(); } /** * A Print Job exists when the timer is running or SD is printing */ -bool printJobOngoing() { return print_job_timer.isRunning() || IS_SD_PRINTING(); } +bool Marlin::printJobOngoing() { return print_job_timer.isRunning() || card.isStillPrinting(); } /** * Printing is active when a job is underway but not paused */ -bool printingIsActive() { return !did_pause_print && printJobOngoing(); } +bool Marlin::printingIsActive() { return !did_pause_print && printJobOngoing(); } /** * Printing is paused according to SD or host indicators */ -bool printingIsPaused() { - return did_pause_print || print_job_timer.isPaused() || IS_SD_PAUSED(); +bool Marlin::printingIsPaused() { + return did_pause_print || print_job_timer.isPaused() || card.isPaused(); } -void startOrResumeJob() { +void Marlin::startOrResumeJob() { if (!printingIsPaused()) { TERN_(GCODE_REPEAT_MARKERS, repeat.reset()); TERN_(CANCEL_OBJECTS, cancelable.reset()); TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator = 0); - #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - ui.reset_remaining_time(); - #endif + TERN_(SET_REMAINING_TIME, ui.reset_remaining_time()); + TERN_(HAS_PRUSA_MMU3, MMU3::operation_statistics.reset_per_print_stats()); } print_job_timer.start(); } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA inline void abortSDPrinting() { IF_DISABLED(NO_SD_AUTOSTART, card.autofile_cancel()); @@ -369,7 +392,7 @@ void startOrResumeJob() { TERN(HAS_CUTTER, cutter.kill(), thermalManager.zero_fan_speeds()); // Full cutter shutdown including ISR control - wait_for_heatup = false; + marlin.heatup_done(); TERN_(POWER_LOSS_RECOVERY, recovery.purge()); @@ -382,13 +405,13 @@ void startOrResumeJob() { inline void finishSDPrinting() { if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued - marlin_state = MF_RUNNING; // Signal to stop trying + marlin.setState(MF_RUNNING); // Signal to stop trying TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine()); - TERN_(DGUS_LCD_UI_MKS, ScreenHandler.SDPrintingFinished()); + TERN_(DGUS_LCD_UI_MKS, screen.sdPrintingFinished()); } } -#endif // SDSUPPORT +#endif // HAS_MEDIA /** * Minimal management of Marlin's core activities: @@ -403,7 +426,7 @@ void startOrResumeJob() { * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT) * - Pulse FET_SAFETY_PIN if it exists */ -inline void manage_inactivity(const bool no_stepper_sleep=false) { +void Marlin::manage_inactivity(const bool no_stepper_sleep/*=false*/) { queue.get_available_commands(); @@ -418,8 +441,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { if (gcode.stepper_max_timed_out(ms)) { SERIAL_ERROR_START(); - SERIAL_ECHOPGM(STR_KILL_PRE); - SERIAL_ECHOLNPGM(STR_KILL_INACTIVE_TIME, parser.command_ptr); + SERIAL_ECHOLN(F(STR_KILL_PRE), F(STR_KILL_INACTIVE_TIME), parser.command_ptr); kill(); } @@ -427,7 +449,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { if (has_blocks) gcode.reset_stepper_timeout(ms); // Reset timeout for M18/M84, M85 max 'kill', and laser. // M18 / M84 : Handle steppers inactive time timeout - #if HAS_DISABLE_INACTIVE_AXIS + #if HAS_DISABLE_IDLE_AXES if (gcode.stepper_inactive_time) { static bool already_shutdown_steppers; // = false @@ -437,16 +459,16 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { already_shutdown_steppers = true; // Individual axes will be disabled if configured - TERN_(DISABLE_INACTIVE_X, stepper.disable_axis(X_AXIS)); - TERN_(DISABLE_INACTIVE_Y, stepper.disable_axis(Y_AXIS)); - TERN_(DISABLE_INACTIVE_Z, stepper.disable_axis(Z_AXIS)); - TERN_(DISABLE_INACTIVE_I, stepper.disable_axis(I_AXIS)); - TERN_(DISABLE_INACTIVE_J, stepper.disable_axis(J_AXIS)); - TERN_(DISABLE_INACTIVE_K, stepper.disable_axis(K_AXIS)); - TERN_(DISABLE_INACTIVE_U, stepper.disable_axis(U_AXIS)); - TERN_(DISABLE_INACTIVE_V, stepper.disable_axis(V_AXIS)); - TERN_(DISABLE_INACTIVE_W, stepper.disable_axis(W_AXIS)); - TERN_(DISABLE_INACTIVE_E, stepper.disable_e_steppers()); + TERN_(DISABLE_IDLE_X, stepper.disable_axis(X_AXIS)); + TERN_(DISABLE_IDLE_Y, stepper.disable_axis(Y_AXIS)); + TERN_(DISABLE_IDLE_Z, stepper.disable_axis(Z_AXIS)); + TERN_(DISABLE_IDLE_I, stepper.disable_axis(I_AXIS)); + TERN_(DISABLE_IDLE_J, stepper.disable_axis(J_AXIS)); + TERN_(DISABLE_IDLE_K, stepper.disable_axis(K_AXIS)); + TERN_(DISABLE_IDLE_U, stepper.disable_axis(U_AXIS)); + TERN_(DISABLE_IDLE_V, stepper.disable_axis(V_AXIS)); + TERN_(DISABLE_IDLE_W, stepper.disable_axis(W_AXIS)); + TERN_(DISABLE_IDLE_E, stepper.disable_e_steppers()); TERN_(AUTO_BED_LEVELING_UBL, bedlevel.steppers_were_disabled()); } @@ -467,11 +489,16 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #if HAS_KILL - // Check if the kill button was pressed and wait just in case it was an accidental - // key kill key press + // Check if the kill button was pressed and wait to ensure the signal is not noise + // typically caused by poor insulation and grounding on LCD cables. + // Lower numbers here will increase response time and therefore safety rating. + // It is recommended to set this as low as possible without false triggers. // ------------------------------------------------------------------------------- + #ifndef KILL_DELAY + #define KILL_DELAY 250 + #endif + static int killCount = 0; // make the inactivity button a bit less responsive - const int KILL_DELAY = 750; if (kill_state()) killCount++; else if (killCount > 0) @@ -482,13 +509,12 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { // ---------------------------------------------------------------- if (killCount >= KILL_DELAY) { SERIAL_ERROR_START(); - SERIAL_ECHOPGM(STR_KILL_PRE); - SERIAL_ECHOLNPGM(STR_KILL_BUTTON); + SERIAL_ECHOLN(F(STR_KILL_PRE), F(STR_KILL_BUTTON)); kill(); } #endif - #if HAS_FREEZE_PIN + #if ENABLED(FREEZE_FEATURE) stepper.frozen = READ(FREEZE_PIN) == FREEZE_STATE; #endif @@ -496,7 +522,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { // Handle a standalone HOME button constexpr millis_t HOME_DEBOUNCE_DELAY = 1000UL; static millis_t next_home_key_ms; // = 0 - if (!IS_SD_PRINTING() && !READ(HOME_PIN)) { // HOME_PIN goes LOW when pressed + if (!card.isStillPrinting() && !READ(HOME_PIN)) { // HOME_PIN goes LOW when pressed if (ELAPSED(ms, next_home_key_ms)) { next_home_key_ms = ms + HOME_DEBOUNCE_DELAY; LCD_MESSAGE(MSG_AUTO_HOME); @@ -514,12 +540,16 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { constexpr millis_t CUB_DEBOUNCE_DELAY_##N = 250UL; \ static millis_t next_cub_ms_##N; \ if (BUTTON##N##_HIT_STATE == READ(BUTTON##N##_PIN) \ - && (ENABLED(BUTTON##N##_WHEN_PRINTING) || printer_not_busy)) { \ + && (ENABLED(BUTTON##N##_WHEN_PRINTING) || printer_not_busy) \ + ) { \ if (ELAPSED(ms, next_cub_ms_##N)) { \ next_cub_ms_##N = ms + CUB_DEBOUNCE_DELAY_##N; \ CODE; \ - queue.inject(F(BUTTON##N##_GCODE)); \ - TERN_(HAS_MARLINUI_MENU, ui.quick_feedback()); \ + if (ENABLED(BUTTON##N##_IMMEDIATE)) \ + gcode.process_subcommands_now(F(BUTTON##N##_GCODE)); \ + else \ + queue.inject(F(BUTTON##N##_GCODE)); \ + TERN_(HAS_MARLINUI_MENU, ui.quick_feedback()); \ } \ } \ }while(0) @@ -662,33 +692,20 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { TERN_(HOTEND_IDLE_TIMEOUT, hotend_idle.check()); + #if ANY(PSU_CONTROL, AUTO_POWER_CONTROL) && PIN_EXISTS(PS_ON_EDM) + if ( ELAPSED(ms, powerManager.last_state_change_ms, PS_EDM_RESPONSE) + && (READ(PS_ON_PIN) != READ(PS_ON_EDM_PIN) || TERN0(PSU_OFF_REDUNDANT, extDigitalRead(PS_ON1_PIN) != extDigitalRead(PS_ON1_EDM_PIN))) + ) kill(GET_TEXT_F(MSG_POWER_EDM_FAULT)); + #endif + #if ENABLED(EXTRUDER_RUNOUT_PREVENT) if (thermalManager.degHotend(active_extruder) > (EXTRUDER_RUNOUT_MINTEMP) - && ELAPSED(ms, gcode.previous_move_ms + SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS)) + && ELAPSED(ms, gcode.previous_move_ms, SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS)) && !planner.has_blocks_queued() ) { - #if ENABLED(SWITCHING_EXTRUDER) - bool oldstatus; - switch (active_extruder) { - default: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 0); stepper.ENABLE_EXTRUDER(0); break; - #if E_STEPPERS > 1 - case 2: case 3: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 1); stepper.ENABLE_EXTRUDER(1); break; - #if E_STEPPERS > 2 - case 4: case 5: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 2); stepper.ENABLE_EXTRUDER(2); break; - #if E_STEPPERS > 3 - case 6: case 7: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 3); stepper.ENABLE_EXTRUDER(3); break; - #endif // E_STEPPERS > 3 - #endif // E_STEPPERS > 2 - #endif // E_STEPPERS > 1 - } - #else // !SWITCHING_EXTRUDER - bool oldstatus; - switch (active_extruder) { - default: - #define _CASE_EN(N) case N: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, N); stepper.ENABLE_EXTRUDER(N); break; - REPEAT(E_STEPPERS, _CASE_EN); - } - #endif + const int8_t e_stepper = TERN(HAS_SWITCHING_EXTRUDER, active_extruder >> 1, active_extruder); + const bool e_off = !stepper.AXIS_IS_ENABLED(E_AXIS, e_stepper); + if (e_off) stepper.ENABLE_EXTRUDER(e_stepper); const float olde = current_position.e; current_position.e += EXTRUDER_RUNOUT_EXTRUDE; @@ -697,22 +714,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { planner.set_e_position_mm(olde); planner.synchronize(); - #if ENABLED(SWITCHING_EXTRUDER) - switch (active_extruder) { - default: if (oldstatus) stepper.ENABLE_EXTRUDER(0); else stepper.DISABLE_EXTRUDER(0); break; - #if E_STEPPERS > 1 - case 2: case 3: if (oldstatus) stepper.ENABLE_EXTRUDER(1); else stepper.DISABLE_EXTRUDER(1); break; - #if E_STEPPERS > 2 - case 4: case 5: if (oldstatus) stepper.ENABLE_EXTRUDER(2); else stepper.DISABLE_EXTRUDER(2); break; - #endif // E_STEPPERS > 2 - #endif // E_STEPPERS > 1 - } - #else // !SWITCHING_EXTRUDER - switch (active_extruder) { - #define _CASE_RESTORE(N) case N: if (oldstatus) stepper.ENABLE_EXTRUDER(N); else stepper.DISABLE_EXTRUDER(N); break; - REPEAT(E_STEPPERS, _CASE_RESTORE); - } - #endif // !SWITCHING_EXTRUDER + if (e_off) stepper.DISABLE_EXTRUDER(e_stepper); gcode.reset_stepper_timeout(ms); } @@ -720,9 +722,9 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #if ENABLED(DUAL_X_CARRIAGE) // handle delayed move timeout - if (delayed_move_time && ELAPSED(ms, delayed_move_time) && IsRunning()) { + if (delayed_move_time && ELAPSED(ms, delayed_move_time) && isRunning()) { // travel moves have been received so enact them - delayed_move_time = 0xFFFFFFFFUL; // force moves to be done + delayed_move_time = UINT32_MAX; // force moves to be done destination = current_position; prepare_line_to_destination(); planner.synchronize(); @@ -749,7 +751,12 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { WRITE(FET_SAFETY_PIN, FET_SAFETY_INVERTED); } #endif -} + +} // Marlin::manage_inactivity() + +#if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) + #include "feature/babystep.h" +#endif /** * Standard idle routine keeps the machine alive: @@ -773,14 +780,14 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { * - Update the Průša MMU2 * - Handle Joystick jogging */ -void idle(bool no_stepper_sleep/*=false*/) { +void Marlin::idle(const 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); + if (++idle_depth > 5) SERIAL_ECHOLNPGM("Marlin::idle() call depth: ", idle_depth); #endif // Bed Distance Sensor task @@ -796,14 +803,14 @@ void idle(bool no_stepper_sleep/*=false*/) { TERN_(MAX7219_DEBUG, max7219.idle_tasks()); // Return if setup() isn't completed - if (marlin_state == MF_INITIALIZING) goto IDLE_DONE; + if (is(MF_INITIALIZING)) goto IDLE_DONE; // TODO: Still causing errors - (void)check_tool_sensor_stats(active_extruder, true); + TERN_(TOOL_SENSOR, (void)check_tool_sensor_stats(active_extruder, true)); // Handle filament runout sensors #if HAS_FILAMENT_SENSOR - if (TERN1(HAS_PRUSA_MMU2, !mmu2.enabled())) + if (TERN1(HAS_PRUSA_MMU2, !mmu2.enabled()) && TERN1(HAS_PRUSA_MMU3, !mmu3.enabled())) runout.run(); #endif @@ -815,20 +822,17 @@ void idle(bool no_stepper_sleep/*=false*/) { // Handle Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS) - if (IS_SD_PRINTING()) recovery.outage(); + if (card.isStillPrinting()) recovery.outage(); #endif // Run StallGuard endstop checks #if ENABLED(SPI_ENDSTOPS) if (endstops.tmc_spi_homing.any && TERN1(IMPROVE_HOMING_RELIABILITY, ELAPSED(millis(), sg_guard_period))) - LOOP_L_N(i, 4) if (endstops.tmc_spi_homing_check()) break; // Read SGT 4 times per idle loop + for (uint8_t i = 0; i < 4; ++i) if (endstops.tmc_spi_homing_check()) break; // Read SGT 4 times per idle loop #endif // Handle SD Card insert / remove - TERN_(SDSUPPORT, card.manage_media()); - - // Handle USB Flash Drive insert / remove - TERN_(USB_FLASH_DRIVE_SUPPORT, card.diskIODriver()->idle()); + TERN_(HAS_MEDIA, card.manage_media()); // Announce Host Keepalive state (if any) TERN_(HOST_KEEPALIVE_FEATURE, gcode.host_keepalive()); @@ -840,7 +844,11 @@ void idle(bool no_stepper_sleep/*=false*/) { TERN_(HAS_BEEPER, buzzer.tick()); // Handle UI input / draw events - TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update()); + #if ENABLED(SOVOL_SV06_RTS) + RTS_Update(); + #else + ui.update(); + #endif // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) @@ -868,33 +876,47 @@ void idle(bool no_stepper_sleep/*=false*/) { #endif // Update the Průša MMU2 - TERN_(HAS_PRUSA_MMU2, mmu2.mmu_loop()); + #if HAS_PRUSA_MMU3 + mmu3.mmu_loop(); + #elif HAS_PRUSA_MMU2 + mmu2.mmu_loop(); + #endif // Handle Joystick jogging TERN_(POLL_JOG, joystick.inject_jog_moves()); + // Async Babystepping via the Emergency Parser + #if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) + babystep.do_ep_steps(); + #endif + // Direct Stepping TERN_(DIRECT_STEPPING, page_manager.write_responses()); // Update the LVGL interface TERN_(HAS_TFT_LVGL_UI, LV_TASK_HANDLER()); + // Manage Fixed-time Motion Control + TERN_(FT_MOTION, ftMotion.loop()); + IDLE_DONE: TERN_(MARLIN_DEV_MODE, idle_depth--); + return; -} + +} // Marlin::idle() /** * Kill all activity and lock the machine. * After this the machine will need to be reset. */ -void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { +void Marlin::kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { thermalManager.disable_all_heaters(); TERN_(HAS_CUTTER, cutter.kill()); // Full cutter shutdown including ISR control // Echo the LCD message to serial for extra context - if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNF(lcd_error); } + if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLN(lcd_error); } #if HAS_DISPLAY ui.kill_screen(lcd_error ?: GET_TEXT_F(MSG_KILLED), lcd_component ?: FPSTR(NUL_STR)); @@ -914,7 +936,7 @@ void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullp minkill(steppers_off); } -void minkill(const bool steppers_off/*=false*/) { +void Marlin::minkill(const bool steppers_off/*=false*/) { // Wait a short time (allows messages to get out before shutting down. for (int i = 1000; i--;) DELAY_US(600); @@ -936,7 +958,7 @@ void minkill(const bool steppers_off/*=false*/) { TERN_(HAS_SUICIDE, suicide()); - #if EITHER(HAS_KILL, SOFT_RESET_ON_KILL) + #if ANY(HAS_KILL, SOFT_RESET_ON_KILL) // Wait for both KILL and ENC to be released while (TERN0(HAS_KILL, kill_state()) || TERN0(SOFT_RESET_ON_KILL, ui.button_pressed())) @@ -954,28 +976,29 @@ void minkill(const bool steppers_off/*=false*/) { for (;;) hal.watchdog_refresh(); // Wait for RESET button or power-cycle #endif -} + +} // Marlin::minkill /** * Turn off heaters and stop the print in progress * After a stop the machine may be resumed with M999 */ -void stop() { +void Marlin::stop() { thermalManager.disable_all_heaters(); // 'unpause' taken care of in here print_job_timer.stop(); - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) thermalManager.set_fans_paused(false); // Un-pause fans for safety #endif - if (!IsStopped()) { + if (!isStopped()) { SERIAL_ERROR_MSG(STR_ERR_STOPPED); LCD_MESSAGE(MSG_STOPPED); - safe_delay(350); // allow enough time for messages to get out before stopping - marlin_state = MF_STOPPED; + safe_delay(350); // Allow enough time for messages to get out before stopping + setState(MF_STOPPED); } -} +} // Marlin::stop() inline void tmc_standby_setup() { #if PIN_EXISTS(X_STDBY) @@ -1044,7 +1067,7 @@ inline void tmc_standby_setup() { #if PIN_EXISTS(E7_STDBY) SET_INPUT_PULLDOWN(E7_STDBY_PIN); #endif -} +} // tmc_standby_setup() /** * Marlin Firmware entry-point. Abandon Hope All Ye Who Enter Here. @@ -1075,7 +1098,7 @@ inline void tmc_standby_setup() { * - Init the buzzer, possibly a custom timer * - Init more optional hardware: * • Color LED illumination - * • Neopixel illumination + * • NeoPixel illumination * • Controller Fan * • Creality DWIN LCD (show boot image) * • Tare the Probe if possible @@ -1151,7 +1174,7 @@ void setup() { #if ENABLED(MARLIN_DEV_MODE) auto log_current_ms = [&](PGM_P const msg) { SERIAL_ECHO_START(); - SERIAL_CHAR('['); SERIAL_ECHO(millis()); SERIAL_ECHOPGM("] "); + TSS('[', millis(), F("] ")).echo(); SERIAL_ECHOLNPGM_P(msg); }; #define SETUP_LOG(M) log_current_ms(PSTR(M)) @@ -1164,6 +1187,12 @@ void setup() { millis_t serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL1.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + #if ENABLED(SOVOL_SV06_RTS) + LCD_SERIAL.begin(BAUDRATE); + serial_connect_timeout = millis() + 1000UL; + while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + #endif + #if HAS_MULTI_SERIAL && !HAS_ETHERNET #ifndef BAUDRATE_2 #define BAUDRATE_2 BAUDRATE @@ -1233,6 +1262,12 @@ void setup() { #if TEMP_SENSOR_IS_MAX_TC(1) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1)) OUT_WRITE(TEMP_1_CS_PIN, HIGH); #endif + #if TEMP_SENSOR_IS_MAX_TC(2) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E2)) + OUT_WRITE(TEMP_2_CS_PIN, HIGH); + #endif + #if TEMP_SENSOR_IS_MAX_TC(BED) + OUT_WRITE(TEMP_BED_CS_PIN, HIGH); + #endif #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) OUT_WRITE(SMART_EFFECTOR_MOD_PIN, LOW); // Put Smart Effector into NORMAL mode @@ -1242,7 +1277,7 @@ void setup() { SETUP_RUN(runout.setup()); #endif - #if HAS_TMC220x + #if HAS_TMC_UART SETUP_RUN(tmc_serial_begin()); #endif @@ -1268,7 +1303,9 @@ void setup() { SETUP_RUN(hal.init_board()); - SETUP_RUN(esp_wifi_init()); + #if ENABLED(WIFISUPPORT) + SETUP_RUN(esp_wifi_init()); + #endif // Report Reset Reason if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); @@ -1279,7 +1316,7 @@ void setup() { // Identify myself as Marlin x.x.x SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); - #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) + #ifdef STRING_DISTRIBUTION_DATE SERIAL_ECHO_MSG( " Last Updated: " STRING_DISTRIBUTION_DATE " | Author: " STRING_CONFIG_H_AUTHOR @@ -1313,8 +1350,11 @@ void setup() { // UI must be initialized before EEPROM // (because EEPROM code calls the UI). - - SETUP_RUN(ui.init()); + #if ENABLED(SOVOL_SV06_RTS) + SETUP_RUN(RTS_Update()); + #else + SETUP_RUN(ui.init()); + #endif #if PIN_EXISTS(SAFE_POWER) #if HAS_DRIVER_SAFE_POWER_PROTECT @@ -1325,16 +1365,28 @@ void setup() { #endif #endif - #if BOTH(SDSUPPORT, SDCARD_EEPROM_EMULATION) - SETUP_RUN(card.mount()); // Mount media with settings before first_load + #if HAS_MEDIA + SETUP_RUN(card.init()); // Prepare for media usage + #if ANY(SDCARD_EEPROM_EMULATION, POWER_LOSS_RECOVERY) + SETUP_RUN(card.mount()); // Mount media with settings before first_load + #endif + #endif + + // Prepare some LCDs to display early + #if HAS_EARLY_LCD_SETTINGS + SETUP_RUN(settings.load_lcd_state()); + #endif + + #if ALL(HAS_WIRED_LCD, SHOW_BOOTSCREEN) + SETUP_RUN(ui.show_bootscreen()); + const millis_t bootscreen_ms = millis(); #endif SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults) // This also updates variables in the planner, elsewhere - #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) - SETUP_RUN(ui.show_bootscreen()); - const millis_t bootscreen_ms = millis(); + #if ENABLED(CONFIGURABLE_MACHINE_NAME) + SETUP_RUN(ui.reset_status(false)); // machine_name Initialized by settings.load() #endif #if ENABLED(PROBE_TARE) @@ -1349,7 +1401,7 @@ void setup() { SETUP_RUN(touchBt.init()); #endif - TERN_(HAS_M206_COMMAND, current_position += home_offset); // Init current position based on home_offset + TERN_(HAS_HOME_OFFSET, current_position += home_offset); // Init current position based on home_offset sync_plan_position(); // Vital to init stepper/planner equivalent for current_position @@ -1407,7 +1459,7 @@ void setup() { SETUP_RUN(stepper_dac.init()); #endif - #if EITHER(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1 + #if ANY(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1 OUT_WRITE(SOL1_PIN, LOW); // OFF #endif @@ -1582,7 +1634,11 @@ void setup() { SETUP_RUN(stepper_driver_backward_report()); #endif - #if HAS_PRUSA_MMU2 + #if HAS_PRUSA_MMU3 + if (mmu3.mmu_hw_enabled) SETUP_RUN(mmu3.start()); + SETUP_RUN(mmu3.status()); + SETUP_RUN(spooljoin.initStatus()); + #elif HAS_PRUSA_MMU2 SETUP_RUN(mmu2.init()); #endif @@ -1592,11 +1648,13 @@ void setup() { SERIAL_ECHO_TERNARY(err, "BL24CXX Check ", "failed", "succeeded", "!\n"); #endif - #if HAS_DWIN_E3V2_BASIC - SETUP_RUN(DWIN_InitScreen()); + #if ENABLED(DWIN_CREALITY_LCD) + SETUP_RUN(dwinInitScreen()); + #elif ENABLED(SOVOL_SV06_RTS) + SETUP_RUN(rts.init()); #endif - #if HAS_SERVICE_INTERVALS && !HAS_DWIN_E3V2_BASIC + #if HAS_SERVICE_INTERVALS && DISABLED(DWIN_CREALITY_LCD) SETUP_RUN(ui.reset_status(true)); // Show service messages or keep current status #endif @@ -1609,13 +1667,13 @@ void setup() { #endif #if HAS_TFT_LVGL_UI - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (!card.isMounted()) SETUP_RUN(card.mount()); // Mount SD to load graphics and fonts #endif SETUP_RUN(tft_lvgl_init()); #endif - #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) + #if ALL(HAS_WIRED_LCD, SHOW_BOOTSCREEN) const millis_t elapsed = millis() - bootscreen_ms; #if ENABLED(MARLIN_DEV_MODE) SERIAL_ECHOLNPGM("elapsed=", elapsed); @@ -1627,7 +1685,7 @@ void setup() { SETUP_RUN(password.lock_machine()); // Will not proceed until correct password provided #endif - #if BOTH(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) && EITHER(TFT_CLASSIC_UI, TFT_COLOR_UI) + #if ALL(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) && ANY(TFT_CLASSIC_UI, TFT_COLOR_UI) SETUP_RUN(ui.check_touch_calibration()); #endif @@ -1643,17 +1701,31 @@ void setup() { SETUP_RUN(bdl.init(I2C_BD_SDA_PIN, I2C_BD_SCL_PIN, I2C_BD_DELAY)); #endif - marlin_state = MF_RUNNING; + #if HAS_RS485_SERIAL + SETUP_RUN(rs485_init()); + #endif + + #if ENABLED(FT_MOTION) + SETUP_RUN(ftMotion.init()); + #endif + + marlin.setState(MF_RUNNING); + + #ifdef STARTUP_TUNE + // Play a short startup tune before continuing. + constexpr uint16_t tune[] = STARTUP_TUNE; + for (uint8_t i = 0; i < COUNT(tune) - 1; i += 2) BUZZ(tune[i + 1], tune[i]); + #endif SETUP_LOG("setup() completed."); TERN_(MARLIN_TEST_BUILD, runStartupTests()); -} +} // setup() /** * The main Marlin program loop * - * - Call idle() to handle all tasks between G-code commands + * - Call marlin.idle() to handle all tasks between G-code commands * Note that no G-codes from the queue can be executed during idle() * but many G-codes can be called directly anytime like macros. * - Check whether SD card auto-start is needed now. @@ -1665,16 +1737,16 @@ void setup() { */ void loop() { do { - idle(); + marlin.idle(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (card.flag.abort_sd_printing) abortSDPrinting(); - if (marlin_state == MF_SD_COMPLETE) finishSDPrinting(); + if (marlin.is(MF_SD_COMPLETE)) finishSDPrinting(); #endif queue.advance(); - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) powerManager.checkAutoPowerOff(); #endif diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index f80405a302..35482983ec 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -27,20 +27,6 @@ #include #include -void stop(); - -// Pass true to keep steppers from timing out -void idle(bool no_stepper_sleep=false); -inline void idle_no_sleep() { idle(true); } - -#if ENABLED(G38_PROBE_TARGET) - extern uint8_t G38_move; // Flag to tell the ISR that G38 is in progress, and the type - extern bool G38_did_trigger; // Flag from the ISR to indicate the endstop changed -#endif - -void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, const bool steppers_off=false); -void minkill(const bool steppers_off=false); - // Global State of the firmware enum MarlinState : uint8_t { MF_INITIALIZING = 0, @@ -52,35 +38,81 @@ enum MarlinState : uint8_t { MF_WAITING, }; -extern MarlinState marlin_state; -inline bool IsRunning() { return marlin_state >= MF_RUNNING; } -inline bool IsStopped() { return marlin_state == MF_STOPPED; } +typedef bool (*testFunc_t)(); -bool printingIsActive(); -bool printJobOngoing(); -bool printingIsPaused(); -void startOrResumeJob(); +// Delay ensuring that temperatures are updated and the watchdog is kept alive +void safe_delay(millis_t ms); -bool printer_busy(); +// Singleton for Marlin global data and methods -extern bool wait_for_heatup; - -#if HAS_RESUME_CONTINUE - extern bool wait_for_user; - void wait_for_user_response(millis_t ms=0, const bool no_sleep=false); -#endif - -bool pin_is_protected(const pin_t pin); - -#if HAS_SUICIDE - inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_STATE); } -#endif - -#if HAS_KILL - #ifndef KILL_PIN_STATE - #define KILL_PIN_STATE LOW +class Marlin { +public: + #if ENABLED(CONFIGURABLE_MACHINE_NAME) + static MString<64> machine_name; #endif - inline bool kill_state() { return READ(KILL_PIN) == KILL_PIN_STATE; } -#endif + + static MarlinState state; + static void setState(const MarlinState s) { state = s; } + static bool is(const MarlinState s) { return state == s; } + static bool isStopped() { return is(MF_STOPPED); } + static bool isRunning() { return state >= MF_RUNNING; } + + static bool printingIsActive(); + static bool printJobOngoing(); + static bool printingIsPaused(); + static void startOrResumeJob(); + + static bool printer_busy(); + + static void stop(); + + // Maintain all important activities + static void manage_inactivity(const bool no_stepper_sleep=false); + + // Pass true to keep steppers from timing out + static void idle(const bool no_stepper_sleep=false); + static void idle_no_sleep() { idle(true); } + + static void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, const bool steppers_off=false); + static void minkill(const bool steppers_off=false); + + #if HAS_RESUME_CONTINUE + // Global waiting for user response + static bool wait_for_user; + static void wait_start() { wait_for_user = true; } + static void user_resume() { wait_for_user = false; } + static void wait_for_user_response(millis_t ms=0, const bool no_sleep=false); + #endif + + // Global waiting for heatup state + static bool wait_for_heatup; + static bool is_heating() { return wait_for_heatup; } + static void heatup_start() { wait_for_heatup = true; } + static void heatup_done() { wait_for_heatup = false; } + static void end_waiting() { TERN_(HAS_RESUME_CONTINUE, wait_for_user =) wait_for_heatup = false; } + + // Shared function for M42 / M43 + static bool pin_is_protected(const pin_t pin); + + #if HAS_SUICIDE + static void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_STATE); } + #endif + + static bool kill_state() { + return ( + #if HAS_KILL + #ifndef KILL_PIN_STATE + #define KILL_PIN_STATE LOW + #endif + READ(KILL_PIN) == KILL_PIN_STATE + #else + false + #endif + ); + } + +}; + +extern Marlin marlin; extern const char M112_KILL_STR[]; diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 4e3227ba58..b99fcad89a 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -21,8 +21,14 @@ */ #pragma once +/** + * Whenever changes are made to this file, please update Marlin/Makefile + * and _data/boards.yml in the MarlinDocumentation repo. + */ + #include "macros.h" +#define BOARD_ERROR -2 #define BOARD_UNKNOWN -1 // @@ -49,6 +55,12 @@ #define BOARD_RAMPS_PLUS_EEF 1033 // RAMPS Plus 3DYMY (Power outputs: Hotend0, Hotend1, Fan) #define BOARD_RAMPS_PLUS_SF 1034 // RAMPS Plus 3DYMY (Power outputs: Spindle, Controller Fan) +#define BOARD_RAMPS_BTT_16_PLUS_EFB 1040 // RAMPS 1.6+ (Power outputs: Hotend, Fan, Bed) +#define BOARD_RAMPS_BTT_16_PLUS_EEB 1041 // RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Bed) +#define BOARD_RAMPS_BTT_16_PLUS_EFF 1042 // RAMPS 1.6+ (Power outputs: Hotend, Fan0, Fan1) +#define BOARD_RAMPS_BTT_16_PLUS_EEF 1043 // RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Fan) +#define BOARD_RAMPS_BTT_16_PLUS_SF 1044 // RAMPS 1.6+ (Power outputs: Spindle, Controller Fan) + // // RAMPS Derivatives - ATmega1280, ATmega2560 // @@ -68,55 +80,60 @@ #define BOARD_MKS_GEN_13 1112 // MKS GEN v1.3 or 1.4 #define BOARD_MKS_GEN_L 1113 // MKS GEN L #define BOARD_KFB_2 1114 // BigTreeTech or BIQU KFB2.0 -#define BOARD_ZRIB_V20 1115 // zrib V2.0 (Chinese RAMPS replica) -#define BOARD_ZRIB_V52 1116 // zrib V5.2 (Chinese RAMPS replica) -#define BOARD_FELIX2 1117 // Felix 2.0+ Electronics Board (RAMPS like) -#define BOARD_RIGIDBOARD 1118 // Invent-A-Part RigidBoard -#define BOARD_RIGIDBOARD_V2 1119 // Invent-A-Part RigidBoard V2 -#define BOARD_SAINSMART_2IN1 1120 // Sainsmart 2-in-1 board -#define BOARD_ULTIMAKER 1121 // Ultimaker -#define BOARD_ULTIMAKER_OLD 1122 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) -#define BOARD_AZTEEG_X3 1123 // Azteeg X3 -#define BOARD_AZTEEG_X3_PRO 1124 // Azteeg X3 Pro -#define BOARD_ULTIMAIN_2 1125 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) -#define BOARD_RUMBA 1126 // Rumba -#define BOARD_RUMBA_RAISE3D 1127 // Raise3D N series Rumba derivative -#define BOARD_RL200 1128 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv) -#define BOARD_FORMBOT_TREX2PLUS 1129 // Formbot T-Rex 2 Plus -#define BOARD_FORMBOT_TREX3 1130 // Formbot T-Rex 3 -#define BOARD_FORMBOT_RAPTOR 1131 // Formbot Raptor -#define BOARD_FORMBOT_RAPTOR2 1132 // Formbot Raptor 2 -#define BOARD_BQ_ZUM_MEGA_3D 1133 // bq ZUM Mega 3D -#define BOARD_MAKEBOARD_MINI 1134 // MakeBoard Mini v2.1.2 by MicroMake -#define BOARD_TRIGORILLA_13 1135 // TriGorilla Anycubic version 1.3-based on RAMPS EFB -#define BOARD_TRIGORILLA_14 1136 // ... Ver 1.4 -#define BOARD_TRIGORILLA_14_11 1137 // ... Rev 1.1 (new servo pin order) -#define BOARD_RAMPS_ENDER_4 1138 // Creality: Ender-4, CR-8 -#define BOARD_RAMPS_CREALITY 1139 // Creality: CR10S, CR20, CR-X -#define BOARD_DAGOMA_F5 1140 // Dagoma F5 -#define BOARD_FYSETC_F6_13 1141 // FYSETC F6 1.3 -#define BOARD_FYSETC_F6_14 1142 // FYSETC F6 1.4 -#define BOARD_DUPLICATOR_I3_PLUS 1143 // Wanhao Duplicator i3 Plus -#define BOARD_VORON 1144 // VORON Design -#define BOARD_TRONXY_V3_1_0 1145 // Tronxy TRONXY-V3-1.0 -#define BOARD_Z_BOLT_X_SERIES 1146 // Z-Bolt X Series -#define BOARD_TT_OSCAR 1147 // TT OSCAR -#define BOARD_OVERLORD 1148 // Overlord/Overlord Pro -#define BOARD_HJC2560C_REV1 1149 // ADIMLab Gantry v1 -#define BOARD_HJC2560C_REV2 1150 // ADIMLab Gantry v2 +#define BOARD_ZRIB_V20 1115 // Zonestar zrib V2.0 (Chinese RAMPS replica) +#define BOARD_ZRIB_V52 1116 // Zonestar zrib V5.2 (Chinese RAMPS replica) +#define BOARD_ZRIB_V53 1117 // Zonestar zrib V5.3 (Chinese RAMPS replica) +#define BOARD_FELIX2 1118 // Felix 2.0+ Electronics Board (RAMPS like) +#define BOARD_RIGIDBOARD 1119 // Invent-A-Part RigidBoard +#define BOARD_RIGIDBOARD_V2 1120 // Invent-A-Part RigidBoard V2 +#define BOARD_SAINSMART_2IN1 1121 // Sainsmart 2-in-1 board +#define BOARD_ULTIMAKER 1122 // Ultimaker +#define BOARD_ULTIMAKER_OLD 1123 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) +#define BOARD_AZTEEG_X3 1124 // Azteeg X3 +#define BOARD_AZTEEG_X3_PRO 1125 // Azteeg X3 Pro +#define BOARD_ULTIMAIN_2 1126 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) +#define BOARD_RUMBA 1127 // Rumba +#define BOARD_RUMBA_RAISE3D 1128 // Raise3D N series Rumba derivative +#define BOARD_RL200 1129 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv) +#define BOARD_FORMBOT_TREX2PLUS 1130 // Formbot T-Rex 2 Plus +#define BOARD_FORMBOT_TREX3 1131 // Formbot T-Rex 3 +#define BOARD_FORMBOT_RAPTOR 1132 // Formbot Raptor +#define BOARD_FORMBOT_RAPTOR2 1133 // Formbot Raptor 2 +#define BOARD_BQ_ZUM_MEGA_3D 1134 // bq ZUM Mega 3D +#define BOARD_MAKEBOARD_MINI 1135 // MakeBoard Mini v2.1.2 by MicroMake +#define BOARD_TRIGORILLA_13 1136 // TriGorilla Anycubic version 1.3-based on RAMPS EFB +#define BOARD_TRIGORILLA_14 1137 // ... Ver 1.4 +#define BOARD_TRIGORILLA_14_11 1138 // ... Rev 1.1 (new servo pin order) +#define BOARD_RAMPS_ENDER_4 1139 // Creality: Ender-4, CR-8 +#define BOARD_RAMPS_CREALITY 1140 // Creality: CR10S, CR20, CR-X +#define BOARD_CREALITY_V252 1141 // Creality CR-10 V2, CR-10 V3 +#define BOARD_DAGOMA_F5 1142 // Dagoma F5 +#define BOARD_DAGOMA_D6 1143 // Dagoma D6 (as found in the Dagoma DiscoUltimate V2 TMC) +#define BOARD_FYSETC_F6_13 1144 // FYSETC F6 1.3 +#define BOARD_FYSETC_F6_14 1145 // FYSETC F6 1.4 +#define BOARD_DUPLICATOR_I3_PLUS 1146 // Wanhao Duplicator i3 Plus +#define BOARD_VORON 1147 // VORON Design +#define BOARD_TRONXY_V3_1_0 1148 // Tronxy TRONXY-V3-1.0 +#define BOARD_Z_BOLT_X_SERIES 1149 // Z-Bolt X Series +#define BOARD_TT_OSCAR 1150 // TT OSCAR #define BOARD_TANGO 1151 // BIQU Tango V1 #define BOARD_MKS_GEN_L_V2 1152 // MKS GEN L V2 #define BOARD_MKS_GEN_L_V21 1153 // MKS GEN L V2.1 #define BOARD_COPYMASTER_3D 1154 // Copymaster 3D #define BOARD_ORTUR_4 1155 // Ortur 4 #define BOARD_TENLOG_D3_HERO 1156 // Tenlog D3 Hero IDEX printer -#define BOARD_RAMPS_S_12_EEFB 1157 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed) -#define BOARD_RAMPS_S_12_EEEB 1158 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed) -#define BOARD_RAMPS_S_12_EFFB 1159 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed) -#define BOARD_LONGER3D_LK1_PRO 1160 // Longer LK1 PRO / Alfawise U20 Pro (PRO version) -#define BOARD_LONGER3D_LKx_PRO 1161 // Longer LKx PRO / Alfawise Uxx Pro (PRO version) -#define BOARD_ZRIB_V53 1162 // Zonestar zrib V5.3 (Chinese RAMPS replica) +#define BOARD_TENLOG_MB1_V23 1157 // Tenlog D3, D5, D6 IDEX Printer +#define BOARD_RAMPS_S_12_EEFB 1158 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed) +#define BOARD_RAMPS_S_12_EEEB 1159 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed) +#define BOARD_RAMPS_S_12_EFFB 1160 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed) +#define BOARD_LONGER3D_LK1_PRO 1161 // Longer LK1 PRO / Alfawise U20 Pro (PRO version) +#define BOARD_LONGER3D_LKx_PRO 1162 // Longer LKx PRO / Alfawise Uxx Pro (PRO version) #define BOARD_PXMALION_CORE_I3 1163 // Pxmalion Core I3 +#define BOARD_PANOWIN_CUTLASS 1164 // Panowin Cutlass (as found in the Panowin F1) +#define BOARD_KODAMA_BARDO 1165 // Kodama Bardo V1.x (as found in the Kodama Trinus) +#define BOARD_XTLW_MFF_V1 1166 // XTLW MFF V1.0 +#define BOARD_XTLW_MFF_V2 1167 // XTLW MFF V2.0 +#define BOARD_RUMBA_E3D 1168 // E3D Rumba BigBox // // RAMBo and derivatives @@ -152,19 +169,24 @@ #define BOARD_GT2560_REV_A_PLUS 1315 // Geeetech GT2560 Rev A+ (with auto level probe) #define BOARD_GT2560_REV_B 1316 // Geeetech GT2560 Rev B #define BOARD_GT2560_V3 1317 // Geeetech GT2560 Rev B for A10(M/T/D) -#define BOARD_GT2560_V4 1318 // Geeetech GT2560 Rev B for A10(M/T/D) -#define BOARD_GT2560_V3_MC2 1319 // Geeetech GT2560 Rev B for Mecreator2 -#define BOARD_GT2560_V3_A20 1320 // Geeetech GT2560 Rev B for A20(M/T/D) -#define BOARD_EINSTART_S 1321 // Einstart retrofit -#define BOARD_WANHAO_ONEPLUS 1322 // Wanhao 0ne+ i3 Mini -#define BOARD_LEAPFROG_XEED2015 1323 // Leapfrog Xeed 2015 -#define BOARD_PICA_REVB 1324 // PICA Shield (original version) -#define BOARD_PICA 1325 // PICA Shield (rev C or later) -#define BOARD_INTAMSYS40 1326 // Intamsys 4.0 (Funmat HT) -#define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct 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.) +#define BOARD_GT2560_V3_MC2 1318 // Geeetech GT2560 Rev B for Mecreator2 +#define BOARD_GT2560_V3_A20 1319 // Geeetech GT2560 Rev B for A20(M/T/D) +#define BOARD_GT2560_V4 1320 // Geeetech GT2560 Rev B for A10(M/T/D) +#define BOARD_GT2560_V4_A20 1321 // Geeetech GT2560 Rev B for A20(M/T/D) +#define BOARD_GT2560_V41B 1322 // Geeetech GT2560 V4.1B for A10(M/T/D) +#define BOARD_EINSTART_S 1323 // Einstart retrofit +#define BOARD_WANHAO_ONEPLUS 1324 // Wanhao 0ne+ i3 Mini +#define BOARD_WANHAO_D9 1325 // Wanhao D9 MK2 +#define BOARD_OVERLORD 1326 // Overlord/Overlord Pro +#define BOARD_HJC2560C_REV1 1327 // ADIMLab Gantry v1 +#define BOARD_HJC2560C_REV2 1328 // ADIMLab Gantry v2 +#define BOARD_LEAPFROG_XEED2015 1329 // Leapfrog Xeed 2015 +#define BOARD_PICA_REVB 1330 // PICA Shield (original version) +#define BOARD_PICA 1331 // PICA Shield (rev C or later) +#define BOARD_INTAMSYS40 1332 // Intamsys 4.0 (Funmat HT) +#define BOARD_MALYAN_M180 1333 // Malyan M180 Mainboard Version 2 (no display function, direct G-code only) +#define BOARD_PROTONEER_CNC_SHIELD_V3 1334 // Mega controller & Protoneer CNC Shield V3.00 +#define BOARD_WEEDO_62A 1335 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.) // // ATmega1281, ATmega2561 @@ -183,12 +205,13 @@ #define BOARD_MELZI_V2 1503 // Melzi V2 #define BOARD_MELZI_MAKR3D 1504 // Melzi with ATmega1284 (MaKr3d version) #define BOARD_MELZI_CREALITY 1505 // Melzi Creality3D (for CR-10 etc) -#define BOARD_MELZI_MALYAN 1506 // Melzi Malyan M150 -#define BOARD_MELZI_TRONXY 1507 // Tronxy X5S -#define BOARD_STB_11 1508 // STB V1.1 -#define BOARD_AZTEEG_X1 1509 // Azteeg X1 -#define BOARD_ANET_10 1510 // Anet 1.0 (Melzi clone) -#define BOARD_ZMIB_V2 1511 // ZoneStar ZMIB V2 +#define BOARD_MELZI_CREALITY_ENDER2 1506 // Melzi Creality3D (for Ender-2) +#define BOARD_MELZI_MALYAN 1507 // Melzi Malyan M150 +#define BOARD_MELZI_TRONXY 1508 // Tronxy X5S +#define BOARD_STB_11 1509 // STB V1.1 +#define BOARD_AZTEEG_X1 1510 // Azteeg X1 +#define BOARD_ANET_10 1511 // Anet 1.0 (Melzi clone) +#define BOARD_ZMIB_V2 1512 // ZoneStar ZMIB V2 // // Other ATmega644P, ATmega644, ATmega1284P @@ -220,7 +243,7 @@ #define BOARD_5DPRINT 1707 // 5DPrint D8 Driver Board // -// LPC1768 ARM Cortex M3 +// LPC1768 ARM Cortex-M3 // #define BOARD_RAMPS_14_RE_ARM_EFB 2000 // Re-ARM with RAMPS 1.4 (Power outputs: Hotend, Fan, Bed) @@ -241,7 +264,7 @@ #define BOARD_EMOTRONIC 2015 // eMotion-Tech eMotronic // -// LPC1769 ARM Cortex M3 +// LPC1769 ARM Cortex-M3 // #define BOARD_MKS_SGEN 2500 // MKS-SGen @@ -256,14 +279,15 @@ #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 +#define BOARD_XTLW_CLIMBER_8TH_LPC 2512 // XTLW Climber 8 // -// SAM3X8E ARM Cortex M3 +// SAM3X8E ARM Cortex-M3 // #define BOARD_DUE3DOM 3000 // DUE3DOM for Arduino DUE #define BOARD_DUE3DOM_MINI 3001 // DUE3DOM MINI for Arduino DUE -#define BOARD_RADDS 3002 // RADDS +#define BOARD_RADDS 3002 // RADDS v1.5/v1.6 #define BOARD_RAMPS_FD_V1 3003 // RAMPS-FD v1 #define BOARD_RAMPS_FD_V2 3004 // RAMPS-FD v2 #define BOARD_RAMPS_SMART_EFB 3005 // RAMPS-SMART (Power outputs: Hotend, Fan, Bed) @@ -291,172 +315,272 @@ #define BOARD_KRATOS32 3027 // K.3D Kratos32 (Arduino Due Shield) // -// SAM3X8C ARM Cortex M3 +// SAM3X8C ARM Cortex-M3 // #define BOARD_PRINTRBOARD_G2 3100 // Printrboard G2 #define BOARD_ADSK 3101 // Arduino DUE Shield Kit (ADSK) +// +// STM32 ARM Cortex-M0/+ +// + +#define BOARD_BTT_EBB42_V1_1 4000 // BigTreeTech EBB42 V1.1 (STM32G0B1CB) +#define BOARD_BTT_SKR_MINI_E3_V3_0 4001 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B0RE / STM32G0B1RE) +#define BOARD_BTT_MANTA_E3_EZ_V1_0 4002 // BigTreeTech Manta E3 EZ V1.0 (STM32G0B1RE) +#define BOARD_BTT_MANTA_M4P_V2_1 4003 // BigTreeTech Manta M4P V2.1 (STM32G0B0RE) +#define BOARD_BTT_MANTA_M5P_V1_0 4004 // BigTreeTech Manta M5P V1.0 (STM32G0B1RE) +#define BOARD_BTT_MANTA_M8P_V1_0 4005 // BigTreeTech Manta M8P V1.0 (STM32G0B1VE) +#define BOARD_BTT_MANTA_M8P_V1_1 4006 // BigTreeTech Manta M8P V1.1 (STM32G0B1VE) +#define BOARD_BTT_SKRAT_V1_0 4007 // BigTreeTech SKRat V1.0 (STM32G0B1VE) + +// +// STM32 ARM Cortex-M0 +// + +#define BOARD_MALYAN_M200_V2 4100 // STM32F070CB controller +#define BOARD_MALYAN_M300 4101 // STM32F070-based delta +#define BOARD_FLY_D5 4102 // FLY_D5 (STM32F072RB) +#define BOARD_FLY_DP5 4103 // FLY_DP5 (STM32F072RB) +#define BOARD_FLY_D7 4104 // FLY_D7 (STM32F072RB) + // // STM32 ARM Cortex-M3 // -#define BOARD_MALYAN_M200_V2 4000 // STM32F070CB controller -#define BOARD_MALYAN_M300 4001 // STM32F070-based delta -#define BOARD_STM32F103RE 4002 // STM32F103RE Libmaple-based STM32F1 controller -#define BOARD_MALYAN_M200 4003 // STM32C8 Libmaple-based STM32F1 controller -#define BOARD_STM3R_MINI 4004 // STM32F103RE Libmaple-based STM32F1 controller -#define BOARD_GTM32_PRO_VB 4005 // STM32F103VE controller -#define BOARD_GTM32_MINI 4006 // STM32F103VE controller -#define BOARD_GTM32_MINI_A30 4007 // STM32F103VE controller -#define BOARD_GTM32_REV_B 4008 // STM32F103VE controller -#define BOARD_MORPHEUS 4009 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller -#define BOARD_CHITU3D 4010 // Chitu3D (STM32F103RE) -#define BOARD_MKS_ROBIN 4011 // MKS Robin (STM32F103ZE) -#define BOARD_MKS_ROBIN_MINI 4012 // MKS Robin Mini (STM32F103VE) -#define BOARD_MKS_ROBIN_NANO 4013 // MKS Robin Nano (STM32F103VE) -#define BOARD_MKS_ROBIN_NANO_V2 4014 // MKS Robin Nano V2 (STM32F103VE) -#define BOARD_MKS_ROBIN_LITE 4015 // MKS Robin Lite/Lite2 (STM32F103RC) -#define BOARD_MKS_ROBIN_LITE3 4016 // MKS Robin Lite3 (STM32F103RC) -#define BOARD_MKS_ROBIN_PRO 4017 // MKS Robin Pro (STM32F103ZE) -#define BOARD_MKS_ROBIN_E3 4018 // MKS Robin E3 (STM32F103RC) -#define BOARD_MKS_ROBIN_E3_V1_1 4019 // MKS Robin E3 V1.1 (STM32F103RC) -#define BOARD_MKS_ROBIN_E3D 4020 // MKS Robin E3D (STM32F103RC) -#define BOARD_MKS_ROBIN_E3D_V1_1 4021 // MKS Robin E3D V1.1 (STM32F103RC) -#define BOARD_MKS_ROBIN_E3P 4022 // MKS Robin E3p (STM32F103VE) -#define BOARD_BTT_SKR_MINI_V1_1 4023 // BigTreeTech SKR Mini v1.1 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_0 4024 // BigTreeTech SKR Mini E3 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_2 4025 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC / STM32F103RE) -#define BOARD_BTT_SKR_MINI_E3_V3_0 4027 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B1RE) -#define BOARD_BTT_SKR_MINI_MZ_V1_0 4028 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) -#define BOARD_BTT_SKR_E3_DIP 4029 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) -#define BOARD_BTT_SKR_CR6 4030 // BigTreeTech SKR CR6 v1.0 (STM32F103RE) -#define BOARD_JGAURORA_A5S_A1 4031 // JGAurora A5S A1 (STM32F103ZE) -#define BOARD_FYSETC_AIO_II 4032 // FYSETC AIO_II (STM32F103RC) -#define BOARD_FYSETC_CHEETAH 4033 // FYSETC Cheetah (STM32F103RC) -#define BOARD_FYSETC_CHEETAH_V12 4034 // FYSETC Cheetah V1.2 (STM32F103RC) -#define BOARD_LONGER3D_LK 4035 // Longer3D LK1/2 - Alfawise U20/U20+/U30 (STM32F103VE) -#define BOARD_CCROBOT_MEEB_3DP 4036 // ccrobot-online.com MEEB_3DP (STM32F103RC) -#define BOARD_CHITU3D_V5 4037 // Chitu3D TronXY X5SA V5 Board (STM32F103ZE) -#define BOARD_CHITU3D_V6 4038 // Chitu3D TronXY X5SA V6 Board (STM32F103ZE) -#define BOARD_CHITU3D_V9 4039 // Chitu3D TronXY X5SA V9 Board (STM32F103ZE) -#define BOARD_CREALITY_V4 4040 // Creality v4.x (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V422 4041 // Creality v4.2.2 (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V423 4042 // Creality v4.2.3 (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V425 4043 // Creality v4.2.5 (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V427 4044 // Creality v4.2.7 (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V4210 4045 // Creality v4.2.10 (STM32F103RC / STM32F103RE) as found in the CR-30 -#define BOARD_CREALITY_V431 4046 // Creality v4.3.1 (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V431_A 4047 // Creality v4.3.1a (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V431_B 4048 // Creality v4.3.1b (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V431_C 4049 // Creality v4.3.1c (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V431_D 4050 // Creality v4.3.1d (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V452 4051 // Creality v4.5.2 (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V453 4052 // Creality v4.5.3 (STM32F103RC / STM32F103RE) -#define BOARD_CREALITY_V24S1 4053 // Creality v2.4.S1 (STM32F103RC / STM32F103RE) v101 as found in the Ender-7 -#define BOARD_CREALITY_V24S1_301 4054 // Creality v2.4.S1_301 (STM32F103RC / STM32F103RE) v301 as found in the Ender-3 S1 -#define BOARD_CREALITY_V25S1 4055 // Creality v2.5.S1 (STM32F103RE) as found in the CR-10 Smart Pro -#define BOARD_TRIGORILLA_PRO 4056 // Trigorilla Pro (STM32F103ZE) -#define BOARD_FLY_MINI 4057 // FLYmaker FLY MINI (STM32F103RC) -#define BOARD_FLSUN_HISPEED 4058 // FLSUN HiSpeedV1 (STM32F103VE) -#define BOARD_BEAST 4059 // STM32F103RE Libmaple-based controller -#define BOARD_MINGDA_MPX_ARM_MINI 4060 // STM32F103ZE Mingda MD-16 -#define BOARD_GTM32_PRO_VD 4061 // STM32F103VE controller -#define BOARD_ZONESTAR_ZM3E2 4062 // Zonestar ZM3E2 (STM32F103RC) -#define BOARD_ZONESTAR_ZM3E4 4063 // Zonestar ZM3E4 V1 (STM32F103VC) -#define BOARD_ZONESTAR_ZM3E4V2 4064 // Zonestar ZM3E4 V2 (STM32F103VC) -#define BOARD_ERYONE_ERY32_MINI 4065 // Eryone Ery32 mini (STM32F103VE) -#define BOARD_PANDA_PI_V29 4066 // Panda Pi V2.9 - Standalone (STM32F103RC) +#define BOARD_STM32F103RE 5000 // STM32F103RE Libmaple-based STM32F1 controller +#define BOARD_MALYAN_M200 5001 // STM32C8 Libmaple-based STM32F1 controller +#define BOARD_STM3R_MINI 5002 // STM32F103RE Libmaple-based STM32F1 controller +#define BOARD_GTM32_PRO_VB 5003 // STM32F103VE controller +#define BOARD_GTM32_PRO_VD 5004 // STM32F103VE controller +#define BOARD_GTM32_MINI 5005 // STM32F103VE controller +#define BOARD_GTM32_MINI_A30 5006 // STM32F103VE controller +#define BOARD_GTM32_REV_B 5007 // STM32F103VE controller +#define BOARD_MORPHEUS 5008 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller +#define BOARD_CHITU3D 5009 // Chitu3D (STM32F103RE) +#define BOARD_MKS_ROBIN 5010 // MKS Robin (STM32F103ZE) +#define BOARD_MKS_ROBIN_MINI 5011 // MKS Robin Mini (STM32F103VE) +#define BOARD_MKS_ROBIN_NANO 5012 // MKS Robin Nano (STM32F103VE) +#define BOARD_MKS_ROBIN_NANO_V2 5013 // MKS Robin Nano V2 (STM32F103VE) +#define BOARD_MKS_ROBIN_LITE 5014 // MKS Robin Lite/Lite2 (STM32F103RC) +#define BOARD_MKS_ROBIN_LITE3 5015 // MKS Robin Lite3 (STM32F103RC) +#define BOARD_MKS_ROBIN_PRO 5016 // MKS Robin Pro (STM32F103ZE) +#define BOARD_MKS_ROBIN_E3 5017 // MKS Robin E3 (STM32F103RC) +#define BOARD_MKS_ROBIN_E3_V1_1 5018 // MKS Robin E3 V1.1 (STM32F103RC) +#define BOARD_MKS_ROBIN_E3D 5019 // MKS Robin E3D (STM32F103RC) +#define BOARD_MKS_ROBIN_E3D_V1_1 5020 // MKS Robin E3D V1.1 (STM32F103RC) +#define BOARD_MKS_ROBIN_E3P 5021 // MKS Robin E3P (STM32F103VE) +#define BOARD_BTT_SKR_MINI_V1_1 5022 // BigTreeTech SKR Mini v1.1 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_0 5023 // BigTreeTech SKR Mini E3 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_2 5024 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V2_0 5025 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC / STM32F103RE) +#define BOARD_BTT_SKR_MINI_MZ_V1_0 5026 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) +#define BOARD_BTT_SKR_E3_DIP 5027 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) +#define BOARD_BTT_SKR_CR6 5028 // BigTreeTech SKR CR6 v1.0 (STM32F103RE) +#define BOARD_JGAURORA_A5S_A1 5029 // JGAurora A5S A1 (STM32F103ZE) +#define BOARD_FYSETC_AIO_II 5030 // FYSETC AIO_II (STM32F103RC) +#define BOARD_FYSETC_CHEETAH 5031 // FYSETC Cheetah (STM32F103RC) +#define BOARD_FYSETC_CHEETAH_V12 5032 // FYSETC Cheetah V1.2 (STM32F103RC) +#define BOARD_LONGER3D_LK 5033 // Longer3D LK1/2 - Alfawise U20/U20+/U30 (STM32F103VE) +#define BOARD_CCROBOT_MEEB_3DP 5034 // ccrobot-online.com MEEB_3DP (STM32F103RC) +#define BOARD_CHITU3D_V5 5035 // Chitu3D TronXY X5SA V5 Board (STM32F103ZE) +#define BOARD_CHITU3D_V6 5036 // Chitu3D TronXY X5SA V6 Board (STM32F103ZE) +#define BOARD_CHITU3D_V9 5037 // Chitu3D TronXY X5SA V9 Board (STM32F103ZE) +#define BOARD_CREALITY_V4 5038 // Creality v4.x (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V422 5039 // Creality v4.2.2 (STM32F103RC / STM32F103RE) ... GD32 Variant Below! +#define BOARD_CREALITY_V423 5040 // Creality v4.2.3 (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V425 5041 // Creality v4.2.5 (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V427 5042 // Creality v4.2.7 (STM32F103RC / STM32F103RE) ... GD32 Variant Below! +#define BOARD_CREALITY_V4210 5043 // Creality v4.2.10 (STM32F103RC / STM32F103RE) as found in the CR-30 +#define BOARD_CREALITY_V431 5044 // Creality v4.3.1 (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V431_A 5045 // Creality v4.3.1a (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V431_B 5046 // Creality v4.3.1b (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V431_C 5047 // Creality v4.3.1c (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V431_D 5048 // Creality v4.3.1d (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V452 5049 // Creality v4.5.2 (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V453 5050 // Creality v4.5.3 (STM32F103RC / STM32F103RE) +#define BOARD_CREALITY_V521 5051 // Creality v5.2.1 (STM32F103VE) as found in the SV04 +#define BOARD_CREALITY_V24S1 5052 // Creality v2.4.S1 (STM32F103RC / STM32F103RE) CR-FDM-v2.4.S1_v101 as found in the Ender-7 +#define BOARD_CREALITY_V24S1_301 5053 // Creality v2.4.S1_301 (STM32F103RC / STM32F103RE) CR-FDM-v24S1_301 as found in the Ender-3 S1 +#define BOARD_CREALITY_V25S1 5054 // Creality v2.5.S1 (STM32F103RE) CR-FDM-v2.5.S1_100 as found in the CR-10 Smart Pro +#define BOARD_TRIGORILLA_PRO 5055 // Trigorilla Pro (STM32F103ZE) +#define BOARD_FLY_MINI 5056 // FLYmaker FLY MINI (STM32F103RC) +#define BOARD_FLSUN_HISPEED 5057 // FLSUN HiSpeedV1 (STM32F103VE) +#define BOARD_BEAST 5058 // STM32F103RE Libmaple-based controller +#define BOARD_MINGDA_MPX_ARM_MINI 5059 // STM32F103ZE Mingda MD-16 +#define BOARD_ZONESTAR_ZM3E2 5060 // Zonestar ZM3E2 (STM32F103RC) +#define BOARD_ZONESTAR_ZM3E4 5061 // Zonestar ZM3E4 V1 (STM32F103VC) +#define BOARD_ZONESTAR_ZM3E4V2 5062 // Zonestar ZM3E4 V2 (STM32F103VC) +#define BOARD_ERYONE_ERY32_MINI 5063 // Eryone Ery32 mini (STM32F103VE) +#define BOARD_PANDA_PI_V29 5064 // Panda Pi V2.9 - Standalone (STM32F103RC) +#define BOARD_SOVOL_V131 5065 // Sovol V1.3.1 (GD32F103RE) +#define BOARD_TRIGORILLA_V006 5066 // Trigorilla V0.0.6 (GD32F103RE) +#define BOARD_KEDI_CONTROLLER_V1_2 5067 // EDUTRONICS Kedi Controller V1.2 (STM32F103RC) +#define BOARD_MD_D301 5068 // Mingda D2 DZ301 V1.0 (STM32F103ZE) +#define BOARD_VOXELAB_AQUILA 5069 // Voxelab Aquila V1.0.0/V1.0.1 (GD32F103RC / N32G455RE / STM32F103RE) +#define BOARD_SPRINGER_CONTROLLER 5070 // ORCA 3D SPRINGER Modular Controller (STM32F103VC) +#define BOARD_ATOMSTACK_FB5_V2 5071 // Atomstack FB5 V2.0 (STM32F103RCT6) // // ARM Cortex-M4F // -#define BOARD_TEENSY31_32 4100 // Teensy3.1 and Teensy3.2 -#define BOARD_TEENSY35_36 4101 // Teensy3.5 and Teensy3.6 +#define BOARD_TEENSY31_32 5100 // Teensy3.1 and Teensy3.2 +#define BOARD_TEENSY35_36 5101 // Teensy3.5 and Teensy3.6 // // STM32 ARM Cortex-M4F // -#define BOARD_ARMED 4200 // Arm'ed STM32F4-based controller -#define BOARD_RUMBA32_V1_0 4201 // RUMBA32 STM32F446VE based controller from Aus3D -#define BOARD_RUMBA32_V1_1 4202 // RUMBA32 STM32F446VE based controller from Aus3D -#define BOARD_RUMBA32_MKS 4203 // RUMBA32 STM32F446VE based controller from Makerbase -#define BOARD_RUMBA32_BTT 4204 // RUMBA32 STM32F446VE based controller from BIGTREETECH -#define BOARD_BLACK_STM32F407VE 4205 // BLACK_STM32F407VE -#define BOARD_BLACK_STM32F407ZE 4206 // BLACK_STM32F407ZE -#define BOARD_BTT_SKR_PRO_V1_1 4207 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) -#define BOARD_BTT_SKR_PRO_V1_2 4208 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) -#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VG) -#define BOARD_BTT_E3_RRF 4210 // BigTreeTech E3 RRF (STM32F407VG) -#define BOARD_BTT_SKR_V2_0_REV_A 4211 // BigTreeTech SKR v2.0 Rev A (STM32F407VG) -#define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VG/STM32F429VG) -#define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT) -#define BOARD_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZE) -#define BOARD_BTT_OCTOPUS_V1_1 4215 // BigTreeTech Octopus v1.1 (STM32F446ZE) -#define BOARD_BTT_OCTOPUS_PRO_V1_0 4216 // BigTreeTech Octopus Pro v1.0 (STM32F446ZE / STM32F429ZG) -#define BOARD_LERDGE_K 4217 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4218 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4219 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4220 // VAkE 403D (STM32F446VE) -#define BOARD_FYSETC_S6 4221 // FYSETC S6 (STM32F446VE) -#define BOARD_FYSETC_S6_V2_0 4222 // FYSETC S6 v2.0 (STM32F446VE) -#define BOARD_FYSETC_SPIDER 4223 // FYSETC Spider (STM32F446VE) -#define BOARD_FLYF407ZG 4224 // FLYmaker FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4225 // MKS_ROBIN2 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 4226 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 4227 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_MKS_ROBIN_NANO_V3_1 4228 // MKS Robin Nano V3.1 (STM32F407VE) -#define BOARD_MKS_MONSTER8_V1 4229 // MKS Monster8 V1 (STM32F407VE) -#define BOARD_MKS_MONSTER8_V2 4230 // MKS Monster8 V2 (STM32F407VE) -#define BOARD_ANET_ET4 4231 // ANET ET4 V1.x (STM32F407VG) -#define BOARD_ANET_ET4P 4232 // ANET ET4P V1.x (STM32F407VG) -#define BOARD_FYSETC_CHEETAH_V20 4233 // FYSETC Cheetah V2.0 (STM32F401RC) -#define BOARD_TH3D_EZBOARD_V2 4234 // TH3D EZBoard v2.0 (STM32F405RG) -#define BOARD_OPULO_LUMEN_REV3 4235 // Opulo Lumen PnP Controller REV3 (STM32F407VE / STM32F407VG) -#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 +#define BOARD_ARMED 5200 // Arm'ed STM32F4-based controller +#define BOARD_RUMBA32_V1_0 5201 // RUMBA32 STM32F446VE based controller from Aus3D +#define BOARD_RUMBA32_V1_1 5202 // RUMBA32 STM32F446VE based controller from Aus3D +#define BOARD_RUMBA32_MKS 5203 // RUMBA32 STM32F446VE based controller from Makerbase +#define BOARD_RUMBA32_BTT 5204 // RUMBA32 STM32F446VE based controller from BIGTREETECH +#define BOARD_BLACK_STM32F407VE 5205 // Black STM32F407VE development board +#define BOARD_BLACK_STM32F407ZE 5206 // Black STM32F407ZE development board +#define BOARD_BTT_SKR_MINI_E3_V3_0_1 5207 // BigTreeTech SKR Mini E3 V3.0.1 (STM32F401RC) +#define BOARD_BTT_SKR_PRO_V1_1 5208 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) +#define BOARD_BTT_SKR_PRO_V1_2 5209 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) +#define BOARD_BTT_BTT002_V1_0 5210 // BigTreeTech BTT002 v1.0 (STM32F407VG) +#define BOARD_BTT_E3_RRF 5211 // BigTreeTech E3 RRF (STM32F407VG) +#define BOARD_BTT_SKR_V2_0_REV_A 5212 // BigTreeTech SKR v2.0 Rev A (STM32F407VG) +#define BOARD_BTT_SKR_V2_0_REV_B 5213 // BigTreeTech SKR v2.0 Rev B (STM32F407VG/STM32F429VG) +#define BOARD_BTT_GTR_V1_0 5214 // BigTreeTech GTR v1.0 (STM32F407IGT) +#define BOARD_BTT_OCTOPUS_V1_0 5215 // BigTreeTech Octopus v1.0 (STM32F446ZE) +#define BOARD_BTT_OCTOPUS_V1_1 5216 // BigTreeTech Octopus v1.1 (STM32F446ZE) +#define BOARD_BTT_OCTOPUS_PRO_V1_0 5217 // BigTreeTech Octopus Pro v1.0 (STM32F446ZE / STM32F429ZG) +#define BOARD_LERDGE_K 5218 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 5219 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 5220 // Lerdge X (STM32F407VE) +#define BOARD_FYSETC_S6 5221 // FYSETC S6 (STM32F446VE) +#define BOARD_FYSETC_S6_V2_0 5222 // FYSETC S6 v2.0 (STM32F446VE) +#define BOARD_FYSETC_SPIDER 5223 // FYSETC Spider (STM32F446VE) +#define BOARD_FYSETC_SPIDER_V2_2 5224 // FYSETC Spider V2.2 (STM32F446VE) +#define BOARD_FLYF407ZG 5225 // FLYmaker FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 5226 // MKS Robin2 V1.0 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 5227 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 5228 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_MKS_ROBIN_NANO_V3_1 5229 // MKS Robin Nano V3.1 (STM32F407VE) +#define BOARD_MKS_MONSTER8_V1 5230 // MKS Monster8 V1 (STM32F407VE) +#define BOARD_MKS_MONSTER8_V2 5231 // MKS Monster8 V2 (STM32F407VE) +#define BOARD_ANET_ET4 5232 // ANET ET4 V1.x (STM32F407VG) +#define BOARD_ANET_ET4P 5233 // ANET ET4P V1.x (STM32F407VG) +#define BOARD_FYSETC_CHEETAH_V20 5234 // FYSETC Cheetah V2.0 (STM32F401RC) +#define BOARD_FYSETC_CHEETAH_V30 5235 // FYSETC Cheetah V3.0 (STM32F446RC) +#define BOARD_TH3D_EZBOARD_V2 5236 // TH3D EZBoard v2.0 (STM32F405RG) +#define BOARD_OPULO_LUMEN_REV3 5237 // Opulo Lumen PnP Controller REV3 (STM32F407VE / STM32F407VG) +#define BOARD_OPULO_LUMEN_REV4 5238 // Opulo Lumen PnP Controller REV4 (STM32F407VE / STM32F407VG) +#define BOARD_MKS_ROBIN_NANO_V1_3_F4 5239 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) +#define BOARD_MKS_EAGLE 5240 // MKS Eagle (STM32F407VE) +#define BOARD_ARTILLERY_RUBY 5241 // Artillery Ruby (STM32F401RC) +#define BOARD_CREALITY_V24S1_301F4 5242 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4 +#define BOARD_CREALITY_CR4NTXXC10 5243 // Creality E3 Free-runs Silent Motherboard (STM32F401RET6) +#define BOARD_FYSETC_SPIDER_KING_V1_F407 5244 // FYSETC Spider King v1 (STM32F407ZG) +#define BOARD_FYSETC_SPIDER_KING_V1_1_F407 5245 // FYSETC Spider King v1.1 (STM32F407ZG) +#define BOARD_MKS_SKIPR_V1 5246 // MKS SKIPR v1.0 all-in-one board (STM32F407VE) +#define BOARD_TRONXY_CXY_446_V10 5247 // TRONXY CXY-446-V10-220413/CXY-V6-191121 (STM32F446ZE) +#define BOARD_CREALITY_F401RE 5248 // Creality CR4NS200141C13 (STM32F401RE) as found in the Ender-5 S1 +#define BOARD_BLACKPILL_CUSTOM 5249 // Custom board based on STM32F401CDU6. +#define BOARD_I3DBEEZ9_V1 5250 // I3DBEEZ9 V1 (STM32F407ZG) +#define BOARD_MELLOW_FLY_E3_V2 5251 // Mellow Fly E3 V2 (STM32F407VG) +#define BOARD_BLACKBEEZMINI_V1 5252 // BlackBeezMini V1 (STM32F401CCU6) +#define BOARD_XTLW_CLIMBER_8TH 5253 // XTLW Climber-8th (STM32F407VGT6) +#define BOARD_FLY_RRF_E3_V1 5254 // Fly RRF E3 V1.0 (STM32F407VG) +#define BOARD_FLY_SUPER8 5255 // Fly SUPER8 (STM32F407ZGT6) +#define BOARD_FLY_D8 5256 // FLY D8 (STM32F407VG) +#define BOARD_FLY_CDY_V3 5257 // FLY CDY V3 (STM32F407VGT6) +#define BOARD_ZNP_ROBIN_NANO 5258 // Elegoo Neptune 2 v1.2 board +#define BOARD_ZNP_ROBIN_NANO_V1_3 5259 // Elegoo Neptune 2 v1.3 board +#define BOARD_MKS_NEPTUNE_X 5260 // Elegoo Neptune X +#define BOARD_MKS_NEPTUNE_3 5261 // Elegoo Neptune 3 // -// ARM Cortex M7 +// Other ARM Cortex-M4 +// +#define BOARD_CREALITY_CR4NS 5300 // Creality CR4NS200320C13 (GD32F303RET6) as found in the Ender-3 V3 SE + +// +// ARM Cortex-M7 // -#define BOARD_REMRAM_V1 5000 // RemRam v1 -#define BOARD_TEENSY41 5001 // Teensy 4.1 -#define BOARD_T41U5XBB 5002 // T41U5XBB Teensy 4.1 breakout board -#define BOARD_NUCLEO_F767ZI 5003 // ST NUCLEO-F767ZI Dev Board -#define BOARD_BTT_SKR_SE_BX_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) +#define BOARD_REMRAM_V1 6000 // RemRam v1 +#define BOARD_NUCLEO_F767ZI 6001 // ST NUCLEO-F767ZI Dev Board +#define BOARD_BTT_SKR_SE_BX_V2 6002 // BigTreeTech SKR SE BX V2.0 (STM32H743II) +#define BOARD_BTT_SKR_SE_BX_V3 6003 // BigTreeTech SKR SE BX V3.0 (STM32H743II) +#define BOARD_BTT_SKR_V3_0 6004 // BigTreeTech SKR V3.0 (STM32H743VI / STM32H723VG) +#define BOARD_BTT_SKR_V3_0_EZ 6005 // BigTreeTech SKR V3.0 EZ (STM32H743VI / STM32H723VG) +#define BOARD_BTT_OCTOPUS_MAX_EZ_V1_0 6006 // BigTreeTech Octopus Max EZ V1.0 (STM32H723ZE) +#define BOARD_BTT_OCTOPUS_PRO_V1_0_1 6007 // BigTreeTech Octopus Pro v1.0.1 (STM32H723ZE) +#define BOARD_BTT_OCTOPUS_PRO_V1_1 6008 // BigTreeTech Octopus Pro v1.1 (STM32H723ZE) +#define BOARD_BTT_MANTA_M8P_V2_0 6009 // BigTreeTech Manta M8P V2.0 (STM32H723ZE) +#define BOARD_BTT_KRAKEN_V1_0 6010 // BigTreeTech Kraken v1.0 (STM32H723ZG) +#define BOARD_TEENSY40 6011 // Teensy 4.0 +#define BOARD_TEENSY41 6012 // Teensy 4.1 +#define BOARD_T41U5XBB 6013 // T41U5XBB Teensy 4.1 breakout board +#define BOARD_FLY_D8_PRO 6014 // FLY_D8_PRO (STM32H723VG) +#define BOARD_FLY_SUPER8_PRO 6015 // FLY SUPER8 PRO (STM32H723ZG) +#define BOARD_FYSETC_SPIDER_KING_V1_H723 6016 // FYSETC Spider King v1 (STM32H723ZG) +#define BOARD_FYSETC_SPIDER_KING_V1_1_H723 6017 // FYSETC Spider King v1.1 (STM32H723ZG) // // Espressif ESP32 WiFi // -#define BOARD_ESPRESSIF_ESP32 6000 // Generic ESP32 -#define BOARD_MRR_ESPA 6001 // MRR ESPA based on ESP32 (native pins only) -#define BOARD_MRR_ESPE 6002 // MRR ESPE based on ESP32 (with I2S stepper stream) -#define BOARD_E4D_BOX 6003 // E4d@BOX -#define BOARD_RESP32_CUSTOM 6004 // Rutilea ESP32 custom board -#define BOARD_FYSETC_E4 6005 // FYSETC E4 -#define BOARD_PANDA_ZHU 6006 // Panda_ZHU -#define BOARD_PANDA_M4 6007 // Panda_M4 -#define BOARD_MKS_TINYBEE 6008 // MKS TinyBee based on ESP32 (with I2S stepper stream) -#define BOARD_ENWI_ESPNP 6009 // enwi ESPNP based on ESP32 (with I2S stepper stream) +#define BOARD_ESPRESSIF_ESP32 7000 // Generic ESP32 +#define BOARD_MRR_ESPA 7001 // MRR ESPA based on ESP32 (native pins only) +#define BOARD_MRR_ESPE 7002 // MRR ESPE based on ESP32 (with I2S stepper stream) +#define BOARD_E4D_BOX 7003 // E4d@BOX +#define BOARD_RESP32_CUSTOM 7004 // Rutilea ESP32 custom board +#define BOARD_FYSETC_E4 7005 // FYSETC E4 +#define BOARD_PANDA_ZHU 7006 // Panda_ZHU +#define BOARD_PANDA_M4 7007 // Panda_M4 +#define BOARD_MKS_TINYBEE 7008 // MKS TinyBee based on ESP32 (with I2S stepper stream) +#define BOARD_ENWI_ESPNP 7009 // enwi ESPNP based on ESP32 (with I2S stepper stream) +#define BOARD_GODI_CONTROLLER_V1_0 7010 // Godi Controller based on ESP32 32-Bit V1.0 +#define BOARD_MM_JOKER 7011 // MagicMaker JOKER based on ESP32 (with I2S stepper stream) // -// SAMD51 ARM Cortex M4 +// SAMD51 ARM Cortex-M4 // -#define BOARD_AGCM4_RAMPS_144 6100 // RAMPS 1.4.4 -#define BOARD_BRICOLEMON_V1_0 6101 // Bricolemon -#define BOARD_BRICOLEMON_LITE_V1_0 6102 // Bricolemon Lite +#define BOARD_AGCM4_RAMPS_144 7100 // RAMPS 1.4.4 +#define BOARD_BRICOLEMON_V1_0 7101 // Bricolemon +#define BOARD_BRICOLEMON_LITE_V1_0 7102 // Bricolemon Lite + +// +// SAMD21 ARM Cortex-M4 +// + +#define BOARD_MINITRONICS20 7103 // Minitronics v2.0 + +// +// HC32 ARM Cortex-M4 +// + +#define BOARD_AQUILA_V101 7200 // Voxelab Aquila V1.0.0/1/2/3 (e.g., Aquila X2, C2). ... GD32 Variant Below! +#define BOARD_CREALITY_ENDER2P_V24S4 7201 // Creality Ender 2 Pro v2.4.S4_170 (HC32f460kcta) + +// +// GD32 ARM Cortex-M3 +// + +#define BOARD_AQUILA_V101_GD32_MFL 7300 // Voxelab Aquila V1.0.1 MFL (GD32F103RC) ... STM32/HC32 Variant Above! + +// +// GD32 ARM Cortex-M4 +// + +#define BOARD_CREALITY_V422_GD32_MFL 7400 // Creality V4.2.2 MFL (GD32F303RE) ... STM32 Variant Above! +#define BOARD_CREALITY_V427_GD32_MFL 7401 // Creality V4.2.7 MFL (GD32F303RE) ... STM32 Variant Above! + +// +// Raspberry Pi +// + +#define BOARD_RP2040 6200 // Generic RP2040 Test board +#define BOARD_RASPBERRY_PI_PICO 6201 // Raspberry Pi Pico +#define BOARD_BTT_SKR_PICO 6202 // BigTreeTech SKR Pico 1.x // // Custom board @@ -468,7 +592,7 @@ // Simulations // -#define BOARD_LINUX_RAMPS 9999 +#define BOARD_SIMULATED 9999 // Simulated 3D Printer with LCD / TFT for development #define _MB_1(B) (defined(BOARD_##B) && MOTHERBOARD==BOARD_##B) #define MB(V...) DO(MB,||,V) diff --git a/Marlin/src/core/bug_on.h b/Marlin/src/core/bug_on.h index 7f1243ed40..8ff565ff73 100644 --- a/Marlin/src/core/bug_on.h +++ b/Marlin/src/core/bug_on.h @@ -27,12 +27,12 @@ // Useful macro for stopping the CPU on an unexpected condition // This is used like SERIAL_ECHOPGM, that is: a key-value call of the local variables you want // to dump to the serial port before stopping the CPU. - // \/ Don't replace by SERIAL_ECHOPGM since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building - #define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": "); SERIAL_ECHOLNPGM(V); SERIAL_FLUSHTX(); *(char*)0 = 42; } while(0) + // \/ Don't use SERIAL_ECHOPGM with ONLY_FILENAME. It can't be a PGM string, + #define BUG_ON(V...) do { SERIAL_ECHOLN(ONLY_FILENAME, __LINE__, F(": ")); SERIAL_ECHOLNPGM(V); SERIAL_FLUSHTX(); *(char*)0 = 42; } while(0) #elif ENABLED(MARLIN_DEV_MODE) // Don't stop the CPU here, but at least dump the bug on the serial port - // \/ Don't replace by SERIAL_ECHOPGM since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building - #define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": BUG!"); SERIAL_ECHOLNPGM(V); SERIAL_FLUSHTX(); } while(0) + // \/ Don't use SERIAL_ECHOPGM with ONLY_FILENAME. It can't be a PGM string, + #define BUG_ON(V...) do { SERIAL_ECHOLN(ONLY_FILENAME, __LINE__, F(": BUG!")); SERIAL_ECHOLNPGM(V); SERIAL_FLUSHTX(); } while(0) #else // Release mode, let's ignore the bug #define BUG_ON(V...) NOOP diff --git a/Marlin/src/core/debug_out.h b/Marlin/src/core/debug_out.h index eb1c91e507..8f14f05c79 100644 --- a/Marlin/src/core/debug_out.h +++ b/Marlin/src/core/debug_out.h @@ -29,23 +29,18 @@ #undef DEBUG_SECTION #undef DEBUG_ECHO_START #undef DEBUG_ERROR_START +#undef DEBUG_WARN_START #undef DEBUG_CHAR #undef DEBUG_ECHO -#undef DEBUG_DECIMAL -#undef DEBUG_ECHO_F #undef DEBUG_ECHOLN #undef DEBUG_ECHOPGM #undef DEBUG_ECHOLNPGM -#undef DEBUG_ECHOF -#undef DEBUG_ECHOLNF #undef DEBUG_ECHOPGM_P #undef DEBUG_ECHOLNPGM_P -#undef DEBUG_ECHOPAIR_F -#undef DEBUG_ECHOPAIR_F_P -#undef DEBUG_ECHOLNPAIR_F -#undef DEBUG_ECHOLNPAIR_F_P #undef DEBUG_ECHO_MSG #undef DEBUG_ERROR_MSG +#undef DEBUG_WARN_MSG +#undef DEBUG_ECHO_TERNARY #undef DEBUG_EOL #undef DEBUG_FLUSH #undef DEBUG_POS @@ -60,25 +55,20 @@ #define DEBUG_ECHO_START SERIAL_ECHO_START #define DEBUG_ERROR_START SERIAL_ERROR_START + #define DEBUG_WARN_START SERIAL_WARN_START #define DEBUG_CHAR SERIAL_CHAR #define DEBUG_ECHO SERIAL_ECHO - #define DEBUG_DECIMAL SERIAL_DECIMAL - #define DEBUG_ECHO_F SERIAL_ECHO_F #define DEBUG_ECHOLN SERIAL_ECHOLN #define DEBUG_ECHOPGM SERIAL_ECHOPGM #define DEBUG_ECHOLNPGM SERIAL_ECHOLNPGM - #define DEBUG_ECHOF SERIAL_ECHOF - #define DEBUG_ECHOLNF SERIAL_ECHOLNF #define DEBUG_ECHOPGM SERIAL_ECHOPGM #define DEBUG_ECHOPGM_P SERIAL_ECHOPGM_P - #define DEBUG_ECHOPAIR_F SERIAL_ECHOPAIR_F - #define DEBUG_ECHOPAIR_F_P SERIAL_ECHOPAIR_F_P #define DEBUG_ECHOLNPGM SERIAL_ECHOLNPGM #define DEBUG_ECHOLNPGM_P SERIAL_ECHOLNPGM_P - #define DEBUG_ECHOLNPAIR_F SERIAL_ECHOLNPAIR_F - #define DEBUG_ECHOLNPAIR_F_P SERIAL_ECHOLNPAIR_F_P #define DEBUG_ECHO_MSG SERIAL_ECHO_MSG #define DEBUG_ERROR_MSG SERIAL_ERROR_MSG + #define DEBUG_WARN_MSG SERIAL_WARN_MSG + #define DEBUG_ECHO_TERNARY SERIAL_ECHO_TERNARY #define DEBUG_EOL SERIAL_EOL #define DEBUG_FLUSH SERIAL_FLUSH #define DEBUG_POS SERIAL_POS @@ -91,23 +81,18 @@ #define DEBUG_SECTION(...) NOOP #define DEBUG_ECHO_START() NOOP #define DEBUG_ERROR_START() NOOP + #define DEBUG_WARN_START() NOOP #define DEBUG_CHAR(...) NOOP #define DEBUG_ECHO(...) NOOP - #define DEBUG_DECIMAL(...) NOOP - #define DEBUG_ECHO_F(...) NOOP #define DEBUG_ECHOLN(...) NOOP #define DEBUG_ECHOPGM(...) NOOP #define DEBUG_ECHOLNPGM(...) NOOP - #define DEBUG_ECHOF(...) NOOP - #define DEBUG_ECHOLNF(...) NOOP #define DEBUG_ECHOPGM_P(...) NOOP #define DEBUG_ECHOLNPGM_P(...) NOOP - #define DEBUG_ECHOPAIR_F(...) NOOP - #define DEBUG_ECHOPAIR_F_P(...) NOOP - #define DEBUG_ECHOLNPAIR_F(...) NOOP - #define DEBUG_ECHOLNPAIR_F_P(...) NOOP #define DEBUG_ECHO_MSG(...) NOOP #define DEBUG_ERROR_MSG(...) NOOP + #define DEBUG_WARN_MSG(...) NOOP + #define DEBUG_ECHO_TERNARY(...) NOOP #define DEBUG_EOL() NOOP #define DEBUG_FLUSH() NOOP #define DEBUG_POS(...) NOOP diff --git a/Marlin/src/core/debug_section.h b/Marlin/src/core/debug_section.h index 6e23d9e4ed..6319515b71 100644 --- a/Marlin/src/core/debug_section.h +++ b/Marlin/src/core/debug_section.h @@ -38,12 +38,9 @@ private: bool debug; void echo_msg(FSTR_P const fpre) { - SERIAL_ECHOF(fpre); - if (the_msg) { - SERIAL_CHAR(' '); - SERIAL_ECHOF(the_msg); - } + SERIAL_ECHO(fpre); + if (the_msg) SERIAL_ECHO(C(' '), the_msg); SERIAL_CHAR(' '); - print_pos(current_position); + print_xyz(xyz_pos_t(current_position)); } }; diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 8cf03d342a..80980380a5 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -41,8 +41,7 @@ #define _TMC2208_STANDALONE 0x2208B #define _TMC2209 0x2209A #define _TMC2209_STANDALONE 0x2209B -#define _TMC26X 0x2600A -#define _TMC26X_STANDALONE 0x2600B +#define _TMC2240 0x2240A #define _TMC2660 0x2660A #define _TMC2660_STANDALONE 0x2660B #define _TMC5130 0x5130A @@ -64,7 +63,7 @@ #define AXIS_DRIVER_TYPE_W(T) _AXIS_DRIVER_TYPE(W,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_Y2(T) (HAS_Y2_STEPPER && _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)) @@ -98,16 +97,17 @@ // Does not match standalone configurations #if ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) \ || HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209) \ - || HAS_DRIVER(TMC2660) \ + || HAS_DRIVER(TMC2240) || HAS_DRIVER(TMC2660) \ || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) ) #define HAS_TRINAMIC_CONFIG 1 #endif #define HAS_TRINAMIC HAS_TRINAMIC_CONFIG -#if ( HAS_DRIVER(TMC2130_STANDALONE) || HAS_DRIVER(TMC2160_STANDALONE) \ +#if ( HAS_DRIVER(TMC2100) \ + || HAS_DRIVER(TMC2130_STANDALONE) || HAS_DRIVER(TMC2160_STANDALONE) \ || HAS_DRIVER(TMC2208_STANDALONE) || HAS_DRIVER(TMC2209_STANDALONE) \ - || HAS_DRIVER(TMC26X_STANDALONE) || HAS_DRIVER(TMC2660_STANDALONE) \ + || HAS_DRIVER(TMC2660_STANDALONE) \ || HAS_DRIVER(TMC5130_STANDALONE) || HAS_DRIVER(TMC5160_STANDALONE) ) #define HAS_TRINAMIC_STANDALONE 1 #endif @@ -115,20 +115,33 @@ #if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) #define HAS_TMCX1X0 1 #endif - +#if HAS_TMCX1X0 || HAS_DRIVER(TMC2240) + #define HAS_TMCX1X0_OR_2240 1 +#endif #if HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209) #define HAS_TMC220x 1 #endif +//#if HAS_TMC_220x || HAS_DRIVER(TMC2240) +// #define HAS_TMC22xx 1 +//#endif +//#if HAS_TMCX1X0 || HAS_TMC220x +// #define HAS_TMC_CS_ACTUAL 1 +//#endif +//#if HAS_TMCX1X0 || HAS_DRIVER(TMC2209) +// #define HAS_TMC_SG_RESULT 1 +//#endif #define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ - || AXIS_DRIVER_TYPE(A,TMC2660) \ + || AXIS_DRIVER_TYPE(A,TMC2240) || AXIS_DRIVER_TYPE(A,TMC2660) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) +#define AXIS_IS_TMC_CONFIG AXIS_IS_TMC + // Test for a driver that uses SPI - this allows checking whether a _CS_ pin // is considered sensitive #define AXIS_HAS_SPI(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC26X) || AXIS_DRIVER_TYPE(A,TMC2660) \ + || AXIS_DRIVER_TYPE(A,TMC2240) || AXIS_DRIVER_TYPE(A,TMC2660) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define AXIS_HAS_UART(A) ( AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) ) @@ -139,19 +152,21 @@ #define AXIS_HAS_SW_SERIAL(A) ( AXIS_HAS_UART(A) && !defined(A##_HARDWARE_SERIAL) ) #define AXIS_HAS_STALLGUARD(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC2209) || AXIS_DRIVER_TYPE(A,TMC2240) \ || AXIS_DRIVER_TYPE(A,TMC2660) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define AXIS_HAS_STEALTHCHOP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC2240) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define AXIS_HAS_SG_RESULT(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) ) + || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC2240) ) #define AXIS_HAS_COOLSTEP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \ - || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC2209) || AXIS_DRIVER_TYPE(A,TMC2240) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define _OR_EAH(N,T) || AXIS_HAS_##T(E##N) @@ -182,10 +197,22 @@ #if ANY_AXIS_HAS(SPI) #define HAS_TMC_SPI 1 #endif - -// -// TMC26XX Stepper Drivers -// -#if HAS_DRIVER(TMC26X) - #define HAS_TMC26X 1 +#if HAS_STALLGUARD || HAS_DRIVER(TMC2160_STANDALONE) || HAS_DRIVER(TMC2130_STANDALONE) \ + || HAS_DRIVER(TMC2209_STANDALONE) || HAS_DRIVER(TMC2660_STANDALONE) \ + || HAS_DRIVER(TMC5130_STANDALONE) || HAS_DRIVER(TMC5160_STANDALONE) + #define HAS_DIAG_PINS 1 #endif + +// Hybrid Threshold ranges +#define THRS_TMC2100 65535 +#define THRS_TMC2130 65535 +#define THRS_TMC2160 255 +#define THRS_TMC2208 255 +#define THRS_TMC2209 255 +#define THRS_TMC2240 255 +#define THRS_TMC2660 65535 +#define THRS_TMC5130 65535 +#define THRS_TMC5160 65535 + +#define _DRIVER_THRS(V) CAT(THRS_, V) +#define STEPPER_MAX_THRS(S) _DRIVER_THRS(S##_DRIVER_TYPE) diff --git a/Marlin/src/core/endianness.h b/Marlin/src/core/endianness.h new file mode 100644 index 0000000000..8fa8e40078 --- /dev/null +++ b/Marlin/src/core/endianness.h @@ -0,0 +1,76 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../core/types.h" +#include "../core/macros.h" + +#ifdef __cplusplus + +namespace Endianness { + static constexpr uint32_t _dword = 0x01020304; + static constexpr uint8_t _lsb = (const uint8_t&)_dword; + + static constexpr bool cpuIsLittleEndian = _lsb == 0x04; + static constexpr bool cpuIsBigEndian = _lsb == 0x01; + static_assert(cpuIsLittleEndian ^ cpuIsBigEndian, "Unknown CPU endianness"); + + // constexpr byte swapping for integral types + template static constexpr typename Private::enable_if::value, T>::type swap(T V, T swappedV=(T)0, size_t byteIndex=0) { + return byteIndex == sizeof(T) + ? swappedV + : swap((T)(V >> 8), (swappedV << 8) | (V & (T)0xFF), byteIndex + 1); + } + + // constexpr byte swapping for types derived from integral types (e.g. enums) + template static constexpr typename Private::enable_if< + Private::is_same::type>::value, T>::type swap(T V) { return (T)swap((uint16_t)V); } + template static constexpr typename Private::enable_if< + Private::is_same::type>::value, T>::type swap(T V) { return (T)swap((uint32_t)V); } + template static constexpr typename Private::enable_if< + Private::is_same::type>::value, T>::type swap(T V) { return (T)swap((uint64_t)V); } + + // Generic byte swapping + // CANNOT be used to initialize constexpr declarations + template static constexpr typename Private::enable_if::value && !Private::is_enum::value, T>::type swap(T V) { + union { + T val; + char byte[sizeof(T)]; + } src{}, dst{}; + + src.val = V; + for (uint8_t i = 0; i < sizeof(T); ++i) dst.byte[i] = src.byte[sizeof(T) - i - 1]; + return dst.val; + } + + // Convert to / from known endianness, depending on the host endianness + template static constexpr T toBE(T V) { return cpuIsLittleEndian ? swap(V) : V; } + template static constexpr T toLE(T V) { return cpuIsLittleEndian ? V : swap(V); } + template static constexpr T fromBE(T V) { return cpuIsLittleEndian ? swap(V) : V; } + template static constexpr T fromLE(T V) { return cpuIsLittleEndian ? V : swap(V); } + + // Reads a big/little endian from a pointer and converts it to the host endianness + template static constexpr T fromBE_P(void* V) { return fromBE(*(T*)V); } + template static constexpr T fromLE_P(void* V) { return fromLE(*(T*)V); } +}; + +#endif // __cplusplus diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 157bd69185..837f3885b9 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -55,6 +55,7 @@ // eu Basque-Euskera // fi Finnish // fr French +// fr_na French without accents (DWIN T5UID1 touchscreen) // gl Galician // hr Croatian // hu Hungarian @@ -87,10 +88,7 @@ #undef MACHINE_NAME #define MACHINE_NAME DEFAULT_MACHINE_NAME #endif - -#ifndef MACHINE_UUID - #define MACHINE_UUID DEFAULT_MACHINE_UUID -#endif +#define MACHINE_NAME_SUBST TERN(CONFIGURABLE_MACHINE_NAME, "$", MACHINE_NAME) #define MARLIN_WEBSITE_URL "marlinfw.org" @@ -138,6 +136,7 @@ #define STR_BUSY_PAUSED_FOR_USER "busy: paused for user" #define STR_BUSY_PAUSED_FOR_INPUT "busy: paused for input" #define STR_Z_MOVE_COMP "Z_move_comp" +#define STR_LINE_NO "Line: " #define STR_RESEND "Resend: " #define STR_UNKNOWN_COMMAND "Unknown command: \"" #define STR_ACTIVE_EXTRUDER "Active Extruder: " @@ -153,7 +152,7 @@ #define STR_ERR_ARC_ARGS "G2/G3 bad parameters" #define STR_ERR_PROTECTED_PIN "Protected Pin" #define STR_ERR_M420_FAILED "Failed to enable Bed Leveling" -#define STR_ERR_M428_TOO_FAR "Too far from reference point" +#define STR_ERR_M428_TOO_FAR "Too far from MIN/MAX" #define STR_ERR_M303_DISABLED "PIDTEMP disabled" #define STR_M119_REPORT "Reporting endstop status" #define STR_ON "ON" @@ -164,8 +163,8 @@ #define STR_SOFT_MIN " Min: " #define STR_SOFT_MAX " Max: " -#define STR_SAVED_POS "Position saved" -#define STR_RESTORING_POS "Restoring position" +#define STR_SAVED_POSITION "Saved position #" +#define STR_RESTORING_POSITION "Restoring position #" #define STR_INVALID_POS_SLOT "Invalid slot. Total: " #define STR_DONE "Done." @@ -174,6 +173,7 @@ #define STR_SD_VOL_INIT_FAIL "volume.init failed" #define STR_SD_OPENROOT_FAIL "openRoot failed" #define STR_SD_CARD_OK "SD card ok" +#define STR_SD_CARD_RELEASED "SD card released" #define STR_SD_WORKDIR_FAIL "workDir open failed" #define STR_SD_OPEN_FILE_FAIL "open failed, File: " #define STR_SD_FILE_OPENED "File opened: " @@ -191,6 +191,8 @@ #define STR_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented" #define STR_ERR_HOTEND_TOO_COLD "Hotend too cold" #define STR_ERR_EEPROM_WRITE "Error writing to EEPROM!" +#define STR_ERR_EEPROM_CORRUPT "EEPROM Corrupt" +#define STR_EEPROM_INITIALIZED "EEPROM Initialized" #define STR_FILAMENT_CHANGE_HEAT_LCD "Press button to heat nozzle" #define STR_FILAMENT_CHANGE_INSERT_LCD "Insert filament and press button" @@ -208,6 +210,8 @@ #define STR_KILL_BUTTON "KILL button/pin" // temperature.cpp strings +#define STR_WAIT_FOR_HOTEND "Wait for hotend heating..." +#define STR_WAIT_FOR_BED "Wait for bed heating..." #define STR_PID_AUTOTUNE "PID Autotune" #define STR_PID_AUTOTUNE_START " start" #define STR_PID_BAD_HEATER_ID " failed! Bad heater id" @@ -228,28 +232,34 @@ #define STR_PID_DEBUG_INPUT ": Input " #define STR_PID_DEBUG_OUTPUT " Output " #define STR_INVALID_EXTRUDER_NUM " - Invalid extruder number !" -#define STR_MPC_AUTOTUNE "MPC Autotune" -#define STR_MPC_AUTOTUNE_START " start for " STR_E -#define STR_MPC_AUTOTUNE_INTERRUPTED " interrupted!" -#define STR_MPC_AUTOTUNE_FINISHED " finished! Put the constants below into Configuration.h" + +// MPCTEMP strings +#define STR_MPC_AUTOTUNE_START "MPC Autotune start for " STR_E +#define STR_MPC_AUTOTUNE_INTERRUPTED "MPC Autotune interrupted!" +#define STR_MPC_AUTOTUNE_FINISHED "MPC Autotune finished! Put the constants below into Configuration.h" #define STR_MPC_COOLING_TO_AMBIENT "Cooling to ambient" #define STR_MPC_HEATING_PAST_200 "Heating to over 200C" #define STR_MPC_MEASURING_AMBIENT "Measuring ambient heatloss at " #define STR_MPC_TEMPERATURE_ERROR "Temperature error" +// Temperature Sensors #define STR_HEATER_BED "bed" #define STR_HEATER_CHAMBER "chamber" #define STR_COOLER "cooler" #define STR_MOTHERBOARD "motherboard" +#define STR_SOC "soc" #define STR_PROBE "probe" #define STR_REDUNDANT "redundant " #define STR_LASER_TEMP "laser temperature" +// Misc. Errors, Thermal Runaway #define STR_STOPPED_HEATER ", system stopped! Heater_ID: " +#define STR_DETECTED_TEMP_B " (temp: " +#define STR_DETECTED_TEMP_E ")" #define STR_REDUNDANCY "Heater switched off. Temperature difference between temp sensors is too high !" #define STR_T_HEATING_FAILED "Heating failed" #define STR_T_THERMAL_RUNAWAY "Thermal Runaway" -#define STR_T_MALFUNCTION "Thermal Malfunction" +#define STR_T_THERMAL_MALFUNCTION "Thermal Malfunction" #define STR_T_MAXTEMP "MAXTEMP triggered" #define STR_T_MINTEMP "MINTEMP triggered" #define STR_ERR_PROBING_FAILED "Probing Failed" @@ -265,6 +275,7 @@ #define STR_DEBUG_COMMUNICATION "COMMUNICATION" #define STR_DEBUG_DETAIL "DETAIL" +// Password Security #define STR_PRINTER_LOCKED "Printer locked! (Unlock with M511 or LCD)" #define STR_WRONG_PASSWORD "Incorrect Password" #define STR_PASSWORD_TOO_LONG "Password too long" @@ -275,9 +286,11 @@ // Settings Report Strings #define STR_Z_AUTO_ALIGN "Z Auto-Align" #define STR_BACKLASH_COMPENSATION "Backlash compensation" +#define STR_FT_MOTION "Fixed-Time Motion" #define STR_S_SEG_PER_SEC "S" #define STR_DELTA_SETTINGS "Delta (L R H S XYZ ABC)" #define STR_SCARA_SETTINGS "SCARA" +#define STR_POLAR_SETTINGS "Polar" #define STR_POLARGRAPH_SETTINGS "Polargraph" #define STR_SCARA_P_T_Z "P T Z" #define STR_ENDSTOP_ADJUSTMENT "Endstop adjustment" @@ -286,14 +299,17 @@ #define STR_MAX_ACCELERATION "Max Acceleration (units/s2)" #define STR_MAX_FEEDRATES "Max feedrates (units/s)" #define STR_ACCELERATION_P_R_T "Acceleration (units/s2) (P R T)" +#define STR_HOMING_FEEDRATE "Homing Feedrate" #define STR_TOOL_CHANGING "Tool-changing" #define STR_HOTEND_OFFSETS "Hotend offsets" #define STR_SERVO_ANGLES "Servo Angles" +#define STR_AUTOTEMP "Auto Temp Control" #define STR_HOTEND_PID "Hotend PID" #define STR_BED_PID "Bed PID" #define STR_CHAMBER_PID "Chamber PID" #define STR_STEPS_PER_UNIT "Steps per unit" #define STR_LINEAR_ADVANCE "Linear Advance" +#define STR_NONLINEAR_EXTRUSION "Nonlinear Extrusion" #define STR_CONTROLLER_FAN "Controller Fan" #define STR_STEPPER_MOTOR_CURRENTS "Stepper motor currents" #define STR_RETRACT_S_F_Z "Retract (S F Z)" @@ -304,8 +320,9 @@ #define STR_FILAMENT_RUNOUT_SENSOR "Filament runout sensor" #define STR_DRIVER_STEPPING_MODE "Driver stepping mode" #define STR_STEPPER_DRIVER_CURRENT "Stepper driver current" +#define STR_HOMING_CURRENT "Homing Current (mA)" #define STR_HYBRID_THRESHOLD "Hybrid Threshold" -#define STR_STALLGUARD_THRESHOLD "StallGuard threshold" +#define STR_STALLGUARD_THRESHOLD "StallGuard Threshold" #define STR_HOME_OFFSET "Home offset" #define STR_SOFT_ENDSTOPS "Soft endstops" #define STR_MATERIAL_HEATUP "Material heatup parameters" @@ -317,14 +334,63 @@ #define STR_TEMPERATURE_UNITS "Temperature Units" #define STR_USER_THERMISTORS "User thermistors" #define STR_DELAYED_POWEROFF "Delayed poweroff" +#define STR_STORED_MACROS "Stored macros" + +// +// General axis names +// +#if HAS_X_AXIS + #define AXIS1_NAME 'X' +#endif +#if HAS_Y_AXIS + #define AXIS2_NAME 'Y' +#endif +#if HAS_Z_AXIS + #define AXIS3_NAME 'Z' +#endif +#define STR_X "X" +#define STR_Y "Y" +#define STR_Z "Z" +#define STR_E "E" +#if IS_KINEMATIC + #define STR_A "A" + #define STR_B "B" + #define STR_C "C" +#else + #define STR_A STR_X + #define STR_B STR_Y + #define STR_C STR_Z +#endif +#define STR_X2 STR_A "2" +#define STR_Y2 STR_B "2" +#define STR_Z2 STR_C "2" +#define STR_Z3 STR_C "3" +#define STR_Z4 STR_C "4" +#if CORE_IS_XY || CORE_IS_XZ + #define STEPPER_A_NAME 'A' +#else + #define STEPPER_A_NAME 'X' +#endif +#if CORE_IS_XY || CORE_IS_YZ + #define STEPPER_B_NAME 'B' +#else + #define STEPPER_B_NAME 'Y' +#endif +#if CORE_IS_XZ || CORE_IS_YZ + #define STEPPER_C_NAME 'C' +#else + #define STEPPER_C_NAME 'Z' +#endif // // Endstop Names used by Endstops::report_states // -#define STR_X_MIN "x_min" -#define STR_X_MAX "x_max" -#define STR_X2_MIN "x2_min" -#define STR_X2_MAX "x2_max" +#if HAS_X_AXIS + #define STR_X_MIN "x_min" + #define STR_X_MAX "x_max" + #define STR_X2_MIN "x2_min" + #define STR_X2_MAX "x2_max" +#endif #if HAS_Y_AXIS #define STR_Y_MIN "y_min" @@ -347,26 +413,7 @@ #define STR_Z_PROBE "z_probe" #define STR_PROBE_EN "probe_en" #define STR_FILAMENT "filament" - -// General axis names -#define STR_X "X" -#define STR_Y "Y" -#define STR_Z "Z" -#define STR_E "E" -#if IS_KINEMATIC - #define STR_A "A" - #define STR_B "B" - #define STR_C "C" -#else - #define STR_A "X" - #define STR_B "Y" - #define STR_C "Z" -#endif -#define STR_X2 "X2" -#define STR_Y2 "Y2" -#define STR_Z2 "Z2" -#define STR_Z3 "Z3" -#define STR_Z4 "Z4" +#define STR_CALIBRATION "calibration" // Extra Axis and Endstop Names #if HAS_I_AXIS @@ -501,7 +548,7 @@ #define STR_W "" #endif -#if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) +#if ANY(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) // Custom characters defined in the first 8 characters of the LCD #define LCD_STR_BEDTEMP "\x00" // Print only as a char. This will have 'unexpected' results when used in a string! diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index ddcf27b2b8..4f6b1df98b 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -21,72 +21,22 @@ */ #pragma once -#if !defined(__has_include) +#ifndef __has_include #define __has_include(...) 1 #endif -#define ABCE 4 -#define XYZE 4 -#define ABC 3 -#define XYZ 3 -#define XY 2 - #define _AXIS(A) (A##_AXIS) -#define _XSTOP_ 0x01 -#define _YSTOP_ 0x02 -#define _ZSTOP_ 0x03 -#define _ISTOP_ 0x04 -#define _JSTOP_ 0x05 -#define _KSTOP_ 0x06 -#define _USTOP_ 0x07 -#define _VSTOP_ 0x08 -#define _WSTOP_ 0x09 -#define _XMIN_ 0x11 -#define _YMIN_ 0x12 -#define _ZMIN_ 0x13 -#define _IMIN_ 0x14 -#define _JMIN_ 0x15 -#define _KMIN_ 0x16 -#define _UMIN_ 0x17 -#define _VMIN_ 0x18 -#define _WMIN_ 0x19 -#define _XMAX_ 0x21 -#define _YMAX_ 0x22 -#define _ZMAX_ 0x23 -#define _IMAX_ 0x24 -#define _JMAX_ 0x25 -#define _KMAX_ 0x26 -#define _UMAX_ 0x27 -#define _VMAX_ 0x28 -#define _WMAX_ 0x29 -#define _XDIAG_ 0x31 -#define _YDIAG_ 0x32 -#define _ZDIAG_ 0x33 -#define _IDIAG_ 0x34 -#define _JDIAG_ 0x35 -#define _KDIAG_ 0x36 -#define _UDIAG_ 0x37 -#define _VDIAG_ 0x38 -#define _WDIAG_ 0x39 -#define _E0DIAG_ 0xE0 -#define _E1DIAG_ 0xE1 -#define _E2DIAG_ 0xE2 -#define _E3DIAG_ 0xE3 -#define _E4DIAG_ 0xE4 -#define _E5DIAG_ 0xE5 -#define _E6DIAG_ 0xE6 -#define _E7DIAG_ 0xE7 - #define _FORCE_INLINE_ __attribute__((__always_inline__)) __inline__ #define FORCE_INLINE __attribute__((always_inline)) inline #define NO_INLINE __attribute__((noinline)) #define _UNUSED __attribute__((unused)) -#define __O0 __attribute__((optimize("O0"))) -#define __Os __attribute__((optimize("Os"))) -#define __O1 __attribute__((optimize("O1"))) -#define __O2 __attribute__((optimize("O2"))) -#define __O3 __attribute__((optimize("O3"))) +#define __O0 __attribute__((optimize("O0"))) // No optimization and less debug info +#define __Og __attribute__((optimize("Og"))) // Optimize the debugging experience +#define __Os __attribute__((optimize("Os"))) // Optimize for size +#define __O1 __attribute__((optimize("O1"))) // Try to reduce size and cycles; nothing that takes a lot of time to compile +#define __O2 __attribute__((optimize("O2"))) // Optimize even more +#define __O3 __attribute__((optimize("O3"))) // Optimize yet more #define IS_CONSTEXPR(...) __builtin_constant_p(__VA_ARGS__) // Only valid solution with C++14. Should use std::is_constant_evaluated() in C++20 instead @@ -99,19 +49,17 @@ #define CYCLES_PER_MICROSECOND (F_CPU / 1000000UL) // 16 or 20 on AVR #endif -// Nanoseconds per cycle -#define NANOSECONDS_PER_CYCLE (1000000000.0 / F_CPU) - // Macros to make a string from a macro #define STRINGIFY_(M) #M #define STRINGIFY(M) STRINGIFY_(M) +#define CHARIFY(M) STRINGIFY(M)[0] #define A(CODE) " " CODE "\n\t" #define L(CODE) CODE ":\n\t" // Macros for bit masks #undef _BV -#define _BV(n) (1<<(n)) +#define _BV(b) (1 << (b)) #define TEST(n,b) (!!((n)&_BV(b))) #define SET_BIT_TO(N,B,TF) do{ if (TF) SBI(N,B); else CBI(N,B); }while(0) #ifndef SBI @@ -127,18 +75,22 @@ #define CBI32(n,b) (n &= ~_BV32(b)) #define TBI32(N,B) (N ^= _BV32(B)) +// Macros for common maths operations #define cu(x) ({__typeof__(x) _x = (x); (_x)*(_x)*(_x);}) #define RADIANS(d) ((d)*float(M_PI)/180.0f) #define DEGREES(r) ((r)*180.0f/float(M_PI)) #define HYPOT2(x,y) (sq(x)+sq(y)) #define NORMSQ(x,y,z) (sq(x)+sq(y)+sq(z)) -#define CIRCLE_AREA(R) (float(M_PI) * sq(float(R))) +#define FLOAT_SQ(I) sq(float(I)) +#define CIRCLE_AREA(R) (float(M_PI) * FLOAT_SQ(R)) #define CIRCLE_CIRC(R) (2 * float(M_PI) * float(R)) #define SIGN(a) ({__typeof__(a) _a = (a); (_a>0)-(_a<0);}) #define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1))) +#define FLIP(X) (X = !(X)) + // Macros to constrain values #ifdef __cplusplus @@ -223,53 +175,63 @@ #define _DO_N(W,C,N,V...) __DO_N(W,C,N,V) #define DO(W,C,V...) (_DO_N(W,C,NUM_ARGS(V),V)) -// Macros to support option testing +// Concatenate symbol names, without or with pre-expansion #define _CAT(a,V...) a##V #define CAT(a,V...) _CAT(a,V) +// Recognize "true" values: blank, 1, 0x1, true #define _ISENA_ ~,1 #define _ISENA_1 ~,1 #define _ISENA_0x1 ~,1 #define _ISENA_true ~,1 #define _ISENA(V...) IS_PROBE(V) +// Macros to evaluate simple option switches #define _ENA_1(O) _ISENA(CAT(_IS,CAT(ENA_, O))) #define _DIS_1(O) NOT(_ENA_1(O)) #define ENABLED(V...) DO(ENA,&&,V) #define DISABLED(V...) DO(DIS,&&,V) +#define ANY(V...) !DISABLED(V) +#define ALL(V...) ENABLED(V) +#define NONE(V...) DISABLED(V) #define COUNT_ENABLED(V...) DO(ENA,+,V) +#define MANY(V...) (COUNT_ENABLED(V) > 1) +// Ternary pre-compiler macros conceal non-emitted content from the compiler #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION ? 'A' : 'B' #define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION ? 'A' : '0' #define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION ? 'A' : '1' -#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION ? 'A' : '' #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. +#define IF_DISABLED(O,A) TERN(O,,A) +// "Ternary" that emits or omits the given content +#define EMIT(V...) V +#define OMIT(...) +#define TERN_(O,A) TERF(O,EMIT)(A) // OPTION ? 'A' : '' ; Usage: TERN_(OPTION, EMITTHIS) + +// Call G(...) or swallow with OMIT(...) +#define TERF(O,G) _TERN(_ENA_1(O),OMIT,G) // OPTION ? 'G' : 'OMIT' ; Usage: TERF(OPTION, CALLTHIS)(ARGS...) + +// Macros to conditionally emit array items and function arguments #define _OPTITEM(A...) A, -#define OPTITEM(O,A...) TERN_(O,DEFER4(_OPTITEM)(A)) +#define OPTITEM(O,A...) TERN_(O,DEFER(_OPTITEM)(A)) #define _OPTARG(A...) , A -#define OPTARG(O,A...) TERN_(O,DEFER4(_OPTARG)(A)) +#define OPTARG(O,A...) TERN_(O,DEFER(_OPTARG)(A)) #define _OPTCODE(A) A; -#define OPTCODE(O,A) TERN_(O,DEFER4(_OPTCODE)(A)) +#define OPTCODE(O,A) TERN_(O,DEFER(_OPTCODE)(A)) -// Macros to avoid 'f + 0.0' which is not always optimized away. Minus included for symmetry. +// Macros to avoid operations that aren't always optimized away (e.g., 'f + 0.0' and 'f * 1.0'). // Compiler flags -fno-signed-zeros -ffinite-math-only also cover 'f * 1.0', 'f - f', etc. #define PLUS_TERN0(O,A) _TERN(_ENA_1(O),,+ (A)) // OPTION ? '+ (A)' : '' #define MINUS_TERN0(O,A) _TERN(_ENA_1(O),,- (A)) // OPTION ? '- (A)' : '' +#define MUL_TERN1(O,A) _TERN(_ENA_1(O),,* (A)) // OPTION ? '* (A)' : '' +#define DIV_TERN1(O,A) _TERN(_ENA_1(O),,/ (A)) // OPTION ? '/ (A)' : '' #define SUM_TERN(O,B,A) ((B) PLUS_TERN0(O,A)) // ((B) (OPTION ? '+ (A)' : '')) #define DIFF_TERN(O,B,A) ((B) MINUS_TERN0(O,A)) // ((B) (OPTION ? '- (A)' : '')) - -#define IF_ENABLED TERN_ -#define IF_DISABLED(O,A) TERN(O,,A) - -#define ANY(V...) !DISABLED(V) -#define NONE(V...) DISABLED(V) -#define ALL(V...) ENABLED(V) -#define BOTH(V1,V2) ALL(V1,V2) -#define EITHER(V1,V2) ANY(V1,V2) -#define MANY(V...) (COUNT_ENABLED(V) > 1) +#define MUL_TERN(O,B,A) ((B) MUL_TERN1(O,A)) // ((B) (OPTION ? '* (A)' : '')) +#define DIV_TERN(O,B,A) ((B) DIV_TERN1(O,A)) // ((B) (OPTION ? '/ (A)' : '')) // Macros to support pins/buttons exist testing #define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0) @@ -282,6 +244,7 @@ #define BUTTONS_EXIST(V...) DO(BTNEX,&&,V) #define ANY_BUTTON(V...) DO(BTNEX,||,V) +// Value helper macros #define WITHIN(N,L,H) ((N) >= (L) && (N) <= (H)) #define ISEOL(C) ((C) == '\n' || (C) == '\r') #define NUMERIC(a) WITHIN(a, '0', '9') @@ -289,6 +252,8 @@ #define HEXCHR(a) (NUMERIC(a) ? (a) - '0' : WITHIN(a, 'a', 'f') ? ((a) - 'a' + 10) : WITHIN(a, 'A', 'F') ? ((a) - 'A' + 10) : -1) #define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+') #define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+') + +// Array shorthand #define COUNT(a) (sizeof(a)/sizeof(*a)) #define ZERO(a) memset((void*)a,0,sizeof(a)) #define COPY(a,b) do{ \ @@ -296,6 +261,7 @@ memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \ }while(0) +// Expansion of some code #define CODE_16( A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N; O; P #define CODE_15( A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N; O #define CODE_14( A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N @@ -316,6 +282,7 @@ #define _CODE_N(N,V...) CODE_##N(V) #define CODE_N(N,V...) _CODE_N(N,V) +// Expansion of some non-delimited content #define GANG_16(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A B C D E F G H I J K L M N O P #define GANG_15(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A B C D E F G H I J K L M N O #define GANG_14(A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A B C D E F G H I J K L M N @@ -337,7 +304,19 @@ #define GANG_N(N,V...) _GANG_N(N,V) #define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) -// Macros for initializing arrays +// Expansion of some list items +#define LIST_32(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,EE,FF,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,EE,FF +#define LIST_31(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,EE,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,EE +#define LIST_30(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD +#define LIST_29(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC +#define LIST_28(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,TU,V,W,X,Y,Z,AA,BB +#define LIST_27(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA +#define LIST_26(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z +#define LIST_25(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y +#define LIST_24(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X +#define LIST_23(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W +#define LIST_22(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V +#define LIST_21(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U #define LIST_20(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T #define LIST_19(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S #define LIST_18(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R @@ -369,11 +348,6 @@ #define _JOIN_1(O) (O) #define JOIN_N(N,C,V...) (DO(JOIN,C,LIST_N(N,V))) -#define LOOP_S_LE_N(VAR, S, N) for (uint8_t VAR=(S); VAR<=(N); VAR++) -#define LOOP_S_L_N(VAR, S, N) for (uint8_t VAR=(S); VAR<(N); VAR++) -#define LOOP_LE_N(VAR, N) LOOP_S_LE_N(VAR, 0, N) -#define LOOP_L_N(VAR, N) LOOP_S_L_N(VAR, 0, N) - #define NOOP (void(0)) #define CEILING(x,y) (((x) + (y) - 1) / (y)) @@ -423,6 +397,8 @@ extern "C++" { // C++11 solution that is standards compliant. Return type is deduced automatically + template static constexpr N _MIN(const N val) { return val; } + template static constexpr N _MAX(const N val) { return val; } template static constexpr auto _MIN(const L lhs, const R rhs) -> decltype(lhs + rhs) { return lhs < rhs ? lhs : rhs; } @@ -442,9 +418,9 @@ FORCE_INLINE constexpr T operator|(T x, T y) { return static_cast(static_cast(x) | static_cast(y)); } \ FORCE_INLINE constexpr T operator^(T x, T y) { return static_cast(static_cast(x) ^ static_cast(y)); } \ FORCE_INLINE constexpr T operator~(T x) { return static_cast(~static_cast(x)); } \ - FORCE_INLINE T & operator&=(T &x, T y) { return x &= y; } \ - FORCE_INLINE T & operator|=(T &x, T y) { return x |= y; } \ - FORCE_INLINE T & operator^=(T &x, T y) { return x ^= y; } + FORCE_INLINE T & operator&=(T &x, T y) { x = x & y; return x; } \ + FORCE_INLINE T & operator|=(T &x, T y) { x = x | y; return x; } \ + FORCE_INLINE T & operator^=(T &x, T y) { x = x ^ y; return x; } // C++11 solution that is standard compliant. is not available on all platform namespace Private { @@ -456,7 +432,41 @@ template struct first_type_of { typedef T type; }; template struct first_type_of { typedef T type; }; + + // remove const/volatile type qualifiers + template struct remove_const { typedef T type; }; + template struct remove_const { typedef T type; }; + + template struct remove_volatile { typedef T type; }; + template struct remove_volatile { typedef T type; }; + + template struct remove_cv { typedef typename remove_const::type>::type type; }; + + // test if type is integral + template struct _is_integral { enum { value = false }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template struct is_integral : public _is_integral::type> {}; } + + // enum type check and regression to its underlying integral. + namespace Private { + template struct is_enum { enum { value = __is_enum(T) }; }; + + template::value> struct _underlying_type { using type = __underlying_type(T); }; + template struct _underlying_type { }; + + template struct underlying_type : public _underlying_type { }; + } + // C++11 solution using SFINAE to detect the existence of a member in a class at compile time. // It creates a HasMember structure containing 'value' set to true if the member exists #define HAS_MEMBER_IMPL(Member) \ @@ -541,6 +551,9 @@ #endif +// Limit an index to an array size +#define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1) + // Macros for adding #define INC_0 1 #define INC_1 2 @@ -563,6 +576,17 @@ #define INC_18 19 #define INC_19 20 #define INC_20 21 +#define INC_21 22 +#define INC_22 23 +#define INC_23 24 +#define INC_24 25 +#define INC_25 26 +#define INC_26 27 +#define INC_27 28 +#define INC_28 29 +#define INC_29 30 +#define INC_30 31 +#define INC_31 32 #define INCREMENT_(n) INC_##n #define INCREMENT(n) INCREMENT_(n) @@ -598,6 +622,23 @@ #define DEC_13 12 #define DEC_14 13 #define DEC_15 14 +#define DEC_16 15 +#define DEC_17 16 +#define DEC_18 17 +#define DEC_19 18 +#define DEC_20 19 +#define DEC_21 20 +#define DEC_22 21 +#define DEC_23 22 +#define DEC_24 23 +#define DEC_25 24 +#define DEC_26 25 +#define DEC_27 26 +#define DEC_28 27 +#define DEC_29 28 +#define DEC_30 29 +#define DEC_31 30 +#define DEC_32 31 #define DECREMENT_(n) DEC_##n #define DECREMENT(n) DECREMENT_(n) @@ -629,6 +670,8 @@ // Force define expansion #define EVAL(V...) EVAL16(V) +#define EVAL4096(V...) EVAL2048(EVAL2048(V)) +#define EVAL2048(V...) EVAL1024(EVAL1024(V)) #define EVAL1024(V...) EVAL512(EVAL512(V)) #define EVAL512(V...) EVAL256(EVAL256(V)) #define EVAL256(V...) EVAL128(EVAL128(V)) @@ -650,11 +693,8 @@ #define IF_ELSE(TF) _IF_ELSE(_BOOL(TF)) #define _IF_ELSE(TF) _CAT(_IF_, TF) -#define _IF_1(V...) V _IF_1_ELSE -#define _IF_0(...) _IF_0_ELSE - -#define _IF_1_ELSE(...) -#define _IF_0_ELSE(V...) V +#define _IF_1(V...) V OMIT +#define _IF_0(...) EMIT #define HAS_ARGS(V...) _BOOL(FIRST(_END_OF_ARGUMENTS_ V)()) #define _END_OF_ARGUMENTS_() 0 @@ -706,10 +746,24 @@ ( DEFER2(__RREPEAT2)()(ADD1(_RPT_I),SUB1(_RPT_N),_RPT_OP,V) ) \ ( /* Do nothing */ ) #define __RREPEAT2() _RREPEAT2 -#define RREPEAT_S(S,N,OP) EVAL1024(_RREPEAT(S,SUB##S(N),OP)) -#define RREPEAT(N,OP) RREPEAT_S(0,N,OP) -#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) +#define RREPEAT_S(S,N,OP) EVAL1024(_RREPEAT(S,SUB##S(N),OP)) +#define RREPEAT(N,OP) RREPEAT_S(0,N,OP) +#define RREPEAT_1(N,OP) RREPEAT_S(1,INCREMENT(N),OP) +#define RREPEAT2_S(S,N,OP,V...) EVAL1024(_RREPEAT2(S,SUB##S(N),OP,V)) +#define RREPEAT2(N,OP,V...) RREPEAT2_S(0,N,OP,V) + +// Emit a list of N OP(I) items with ascending counter. +#define _REPLIST(_RPT_I,_RPT_N,_RPT_OP) \ + _RPT_OP(_RPT_I) \ + IF_ELSE(SUB1(_RPT_N)) \ + ( , DEFER2(__REPLIST)()(ADD1(_RPT_I),SUB1(_RPT_N),_RPT_OP) ) \ + ( /* Do nothing */ ) +#define __REPLIST() _REPLIST + +// Repeat a macro, comma-separated, passing S...N-1. +#define REPLIST_S(S,N,OP) EVAL(_REPLIST(S,SUB##S(N),OP)) +#define REPLIST(N,OP) REPLIST_S(0,N,OP) +#define REPLIST_1(N,OP) REPLIST_S(1,INCREMENT(N),OP) // Call OP(A) with each item as an argument #define _MAP(_MAP_OP,A,V...) \ @@ -732,6 +786,18 @@ #define MAPLIST(OP,V...) EVAL(_MAPLIST(OP,V)) // Temperature Sensor Config -#define _HAS_E_TEMP(N) || (TEMP_SENSOR_##N != 0) +#define TEMP_SENSOR(N) TEMP_SENSOR_##N +#define _HAS_E_TEMP(N) || TEMP_SENSOR(N) #define HAS_E_TEMP_SENSOR (0 REPEAT(EXTRUDERS, _HAS_E_TEMP)) -#define TEMP_SENSOR_IS_MAX_TC(T) (TEMP_SENSOR_##T == -5 || TEMP_SENSOR_##T == -3 || TEMP_SENSOR_##T == -2) +#define TEMP_SENSOR_IS_MAX_TC(T) (TEMP_SENSOR(T) == -5 || TEMP_SENSOR(T) == -3 || TEMP_SENSOR(T) == -2) + +#define _UI_NONE 0 +#define _UI_ORIGIN 101 +#define _UI_FYSETC 102 +#define _UI_HIPRECY 103 +#define _UI_MKS 104 +#define _UI_RELOADED 105 +#define _UI_IA_CREALITY 106 +#define _UI_E3S1PRO 107 +#define _DGUS_UI_IS(N) || (CAT(_UI_, DGUS_LCD_UI) == CAT(_UI_, N)) +#define DGUS_UI_IS(V...) (0 MAP(_DGUS_UI_IS, V)) diff --git a/Marlin/src/core/millis_t.h b/Marlin/src/core/millis_t.h index 95bc40e1ec..1d3cc853b3 100644 --- a/Marlin/src/core/millis_t.h +++ b/Marlin/src/core/millis_t.h @@ -28,6 +28,9 @@ typedef uint32_t millis_t; #define SEC_TO_MS(N) millis_t((N)*1000UL) #define MIN_TO_MS(N) SEC_TO_MS((N)*60UL) #define MS_TO_SEC(N) millis_t((N)/1000UL) +#define MS_TO_SEC_PRECISE(N) (float(N)/1000.0f) -#define PENDING(NOW,SOON) ((int32_t)(NOW-(SOON))<0) -#define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON)) +constexpr bool _PENDING(const millis_t now, const millis_t when) { return int32_t(when - now) > 0; } +constexpr bool _PENDING(const millis_t now, const millis_t start, const millis_t interval) { return (now - start) < interval; } +#define PENDING(V...) _PENDING(V) +#define ELAPSED(V...) !_PENDING(V) diff --git a/Marlin/src/core/mstring.h b/Marlin/src/core/mstring.h new file mode 100644 index 0000000000..3ed21950de --- /dev/null +++ b/Marlin/src/core/mstring.h @@ -0,0 +1,322 @@ +/** + * 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 + +/** + * Lightweight string class template providing operators for all common tasks + * and conversion from F() and PSTR() strings into SRAM strings that reside + * on the stack or persistently, with overflow prevention. + * + * Examples: + * + * MString<50> mystr(F("Hello "), intvar, " World"); // "Hello 3 World" + * + * mystr.append(" (", p_float_t(123.4, 2), ')'); // "Hello 3 World (123.40)" + * + * mystr.clear(); + * + * mystr.append(spaces_t(10), repchr_t('-', 5)); // Repeats are sometimes cheaper than strings + * + * mystr.appendf(F(" ... %i/%i"), count, total); // Works like printf, requires F string + * + */ + +#include "types.h" +#include "utility.h" // AXIS_CHAR +#include "../lcd/utf8.h" + +#ifndef DEFAULT_MSTRING_SIZE + #define DEFAULT_MSTRING_SIZE 20 +#endif + +//#define UNSAFE_MSTRING // Don't initialize the string to "" or set a terminating nul +//#define USE_SPRINTF // Use sprintf instead of snprintf +//#define DJB2_HASH // 32-bit hash with Djb2 algorithm +//#define MSTRING_DEBUG // Debug string operations to diagnose memory leaks +//#define FASTER_APPEND // Append without using an intermediate buffer + +// Declare externs for serial debug output +template extern void SERIAL_ECHO(T x); +template extern void SERIAL_ECHOLN(T x); +extern void SERIAL_ECHO(serial_char_t x); +extern void SERIAL_CHAR(char c); + +#define START_OF_UTF8_CHAR(C) (((C) & 0xC0u) != 0x80U) + +#if ENABLED(USE_SPRINTF) + #define SNPRINTF(A, S, V...) sprintf(A, V) + #define SNPRINTF_P(A, S, V...) sprintf_P(A, V) +#else + #define SNPRINTF(V...) snprintf(V) + #define SNPRINTF_P(V...) snprintf_P(V) +#endif + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + +#if DISABLED(UNSAFE_MSTRING) && GCC_VERSION >= 80000 + #pragma GCC diagnostic ignored "-Wstringop-truncation" +#endif + +/** + * @brief MString class template + * @details A class template providing convenient string operators, + * very similar to the Arduino String class, as it turns out. + * + * @tparam SIZE The pre-allocated storage for the string buffer + */ +template +class MString { +protected: + char str[SIZE+1]; +public: + MString() { safety(0); safety(SIZE); } + + template + MString(const T v) { set(v); safety(SIZE); } + + static_assert(SIZE > 0, "Bad SIZE for MString!"); + + void debug(FSTR_P const f) { + #if ENABLED(MSTRING_DEBUG) + SERIAL_ECHOLN(f, C(':'), uintptr_t(str), C(' '), length(), C(' '), str); + #endif + } + + void safety(const int n) { if (SAFE && n <= SIZE) str[n] = '\0'; } + + // Chainable String Setters + MString& set() { str[0] = '\0'; debug(F("clear")); return *this; } + MString& set(char *s) { strlcpy(str, s, SIZE + 1); debug(F("string")); return *this; } + MString& set(const char *s) { return set(const_cast(s)); } + MString& set_P(PGM_P const s) { strlcpy_P(str, s, SIZE + 1); debug(F("pstring")); return *this; } + MString& set(FSTR_P const f) { return set_P(FTOP(f)); } + MString& set(const bool &b) { return set(b ? F("true") : F("false")); } + MString& set(const char c) { str[0] = c; str[1] = '\0'; debug(F("char")); return *this; } + MString& set(const int8_t &i) { SNPRINTF_P(str, SIZE, PSTR("%d"), i); debug(F("int8_t")); return *this; } + MString& set(const short &i) { SNPRINTF_P(str, SIZE, PSTR("%d"), i); debug(F("short")); return *this; } + MString& set(const int &i) { SNPRINTF_P(str, SIZE, PSTR("%d"), i); debug(F("int")); return *this; } + MString& set(const long &l) { SNPRINTF_P(str, SIZE, PSTR("%ld"), l); debug(F("long")); return *this; } + MString& set(const unsigned char &i) { SNPRINTF_P(str, SIZE, PSTR("%u"), i); debug(F("uchar")); return *this; } + MString& set(const unsigned short &i) { SNPRINTF_P(str, SIZE, PSTR("%u"), i); debug(F("ushort")); return *this; } + MString& set(const unsigned int &i) { SNPRINTF_P(str, SIZE, PSTR("%u"), i); debug(F("uint")); return *this; } + MString& set(const unsigned long &l) { SNPRINTF_P(str, SIZE, PSTR("%lu"), l); debug(F("ulong")); return *this; } + MString& set(const float &f) { return set(p_float_t(f, SERIAL_FLOAT_PRECISION)); } + MString& set(const p_float_t &pf) { return set(w_float_t(pf.value, 1, pf.prec)); } + MString& set(const w_float_t &wf) { char f1[20]; return set(dtostrf(wf.value, wf.width, wf.prec, f1)); } + MString& set(const serial_char_t &v) { return set(char(v.c)); } + MString& set(const xyz_pos_t &v) { set(); return append(v); } + MString& set(const xyze_pos_t &v) { set(); return append(v); } + + template + MString& set(const MString &m) { strlcpy(str, &m, SIZE + 1); debug(F("MString")); return *this; } + + MString& setn(char *s, int len) { int c = _MIN(len, SIZE); strlcpy(str, s, c + 1); debug(F("string")); return *this; } + MString& setn(const char *s, int len) { return setn(const_cast(s), len); } + MString& setn_P(PGM_P const s, int len) { int c = _MIN(len, SIZE); strlcpy_P(str, s, c + 1); debug(F("pstring")); return *this; } + MString& setn(FSTR_P const f, int len) { return setn_P(FTOP(f), len); } + + // set(repchr_t('-', 10)) + MString& set(const repchr_t &s) { int c = _MIN(s.count, SIZE); if (c >= 0) { if (c > 0) memset(str, s.asc, c); str[c] = '\0'; } debug(F("repchr_t")); return *this; } + + // set(spaces_t(10)) + MString& set(const spaces_t &s) { repchr_t r(' ', s.count); return set(r); } + + // Set with format string and arguments, like printf + template + MString& setf_P(PGM_P const pfmt, Args... more) { SNPRINTF_P(str, SIZE, pfmt, more...); debug(F("setf_P")); return *this; } + + template + MString& setf(const char *fmt, Args... more) { SNPRINTF(str, SIZE, fmt, more...); debug(F("setf")); return *this; } + + template + MString& setf(FSTR_P const ffmt, Args... more) { return setf_P(FTOP(ffmt), more...); } + + // Chainable String appenders + MString& append() { debug(F("nil")); return *this; } // for macros that might emit no output + MString& append(char *s) { int sz = length(); if (sz < SIZE) strlcpy(str + sz, s, SIZE - sz + 1); debug(F("string")); return *this; } + MString& append(const char *s) { return append(const_cast(s)); } + MString& append_P(PGM_P const s) { int sz = length(); if (sz < SIZE) strlcpy_P(str + sz, s, SIZE - sz + 1); debug(F("pstring")); return *this; } + MString& append(FSTR_P const f) { return append_P(FTOP(f)); } + MString& append(const bool &b) { return append(b ? F("true") : F("false")); } + MString& append(const char c) { int sz = length(); if (sz < SIZE) { str[sz] = c; if (sz < SIZE - 1) str[sz + 1] = '\0'; } debug(F("char")); return *this; } + #if ENABLED(FASTER_APPEND) + MString& append(const int8_t &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("int8_t")); return *this; } + MString& append(const short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("short")); return *this; } + MString& append(const int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("int")); return *this; } + MString& append(const long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%ld", l); debug(F("long")); return *this; } + MString& append(const unsigned char &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("uchar")); return *this; } + MString& append(const unsigned short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("ushort")); return *this; } + MString& append(const unsigned int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("uint")); return *this; } + MString& append(const unsigned long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%lu", l); debug(F("ulong")); return *this; } + #else + MString& append(const int8_t &i) { char buf[ 5]; sprintf(buf, "%d", i); return append(buf); } + MString& append(const short &i) { char buf[12]; sprintf(buf, "%d", i); return append(buf); } + MString& append(const int &i) { char buf[12]; sprintf(buf, "%d", i); return append(buf); } + MString& append(const long &l) { char buf[12]; sprintf(buf, "%ld", l); return append(buf); } + MString& append(const unsigned char &i) { char buf[ 5]; sprintf(buf, "%u", i); return append(buf); } + MString& append(const unsigned short &i) { char buf[11]; sprintf(buf, "%u", i); return append(buf); } + MString& append(const unsigned int &i) { char buf[11]; sprintf(buf, "%u", i); return append(buf); } + MString& append(const unsigned long &l) { char buf[11]; sprintf(buf, "%lu", l); return append(buf); } + #endif + MString& append(const float &f) { return append(p_float_t(f, SERIAL_FLOAT_PRECISION)); } + MString& append(const p_float_t &pf) { return append(w_float_t(pf.value, 1, pf.prec)); } + MString& append(const w_float_t &wf) { char f1[20]; return append(dtostrf(wf.value, wf.width, wf.prec, f1)); } + MString& append(const serial_char_t &v) { return append(char(v.c)); } + MString& append(const xyz_pos_t &v) { LOOP_NUM_AXES(i) { if (i) append(' '); append(AXIS_CHAR(i), v[i]); } debug(F("xyz")); return *this; } + MString& append(const xyze_pos_t &v) { LOOP_LOGICAL_AXES(i) { if (i) append(' '); append(AXIS_CHAR(i), v[i]); } debug(F("xyze")); return *this; } + + template + MString& append(const MString &m) { return append(&m); } + + // Append only if the given space is available + MString& appendn(char *s, int len) { int sz = length(), c = _MIN(len, SIZE - sz); if (c > 0) { strlcpy(str + sz, s, c + 1); } debug(F("string")); return *this; } + MString& appendn(const char *s, int len) { return appendn(const_cast(s), len); } + MString& appendn_P(PGM_P const s, int len) { int sz = length(), c = _MIN(len, SIZE - sz); if (c > 0) { strlcpy_P(str + sz, s, c + 1); } debug(F("pstring")); return *this; } + MString& appendn(FSTR_P const f, int len) { return appendn_P(FTOP(f), len); } + + // append(repchr_t('-', 10)) + MString& append(const repchr_t &s) { + const int sz = length(), c = _MIN(s.count, SIZE - sz); + if (c > 0) { memset(str + sz, s.asc, c); str[sz + c] = '\0'; } + debug(F("repchr")); + return *this; + } + + // append(spaces_t(10)) + MString& append(const spaces_t &s) { return append(repchr_t(' ', s.count)); } + + template + MString& appendf_P(PGM_P const pfmt, Args... more) { + int sz = length(); + if (sz < SIZE) SNPRINTF_P(str + sz, SIZE - sz, pfmt, more...); + debug(F("appendf_P")); + return *this; + } + + template + MString& appendf(const char *fmt, Args... more) { + const int sz = length(); + if (sz < SIZE) SNPRINTF(str + sz, SIZE - sz, fmt, more...); + debug(F("appendf")); + return *this; + } + + template + MString& appendf(FSTR_P const fmt, Args... more) { return appendf_P(FTOP(fmt), more...); } + + // Instantiate with a list of things + template + MString(T arg1, Args... more) { set(arg1); append(more...); } + + // Catch unhandled types to prevent infinite recursion + template MString& append(T) { return append(TERN(MSTRING_DEBUG, typeid(T).name(), '?')); } + + // Take a list of any number of arguments and append them to the string + template + MString& append(T arg1, Args... more) { return append(arg1).append(more...); } + + // Take a list of any number of arguments and set them in the string + template + MString& set(T arg1, Args... more) { return set(arg1).append(more...); } + + // Operator = as shorthand for set() + template + MString& operator=(const T &v) { return set(v); } + + // Operator += as shorthand for append() + template + MString& operator+=(const T &v) { return append(v); } + + // Operator + as shorthand for append-to-copy + template + MString operator+(const T &v) { return MString(str, v); } + + #ifndef __AVR__ + MString(const double d) { set(d); } + MString& set(const double &f) { return set(p_double_t(f, SERIAL_FLOAT_PRECISION)); } + MString& set(const p_double_t &pf) { return set(w_double_t(pf.value, 1, pf.prec)); } + MString& set(const w_double_t &wf) { char d1[20]; return set(dtostrf(wf.value, wf.width, wf.prec, d1)); } + MString& append(const double &f) { return append(p_double_t(f, SERIAL_FLOAT_PRECISION)); } + MString& append(const p_double_t &pf) { return append(w_double_t(pf.value, 1, pf.prec)); } + MString& append(const w_double_t &wf) { char d1[20]; return append(dtostrf(wf.value, wf.width, wf.prec, d1)); } + #endif + + // Get the character at a given index + char operator[](const int i) const { return str[i]; } + + // Cast to char* (explicit?) + operator char* () { return str; } + + // Use &mystring as shorthand for mystring.str + char* operator&() { return str; } + + // Return the buffer address (same as &) + char* buffer() { return str; } + + int length() const { return strlen(str); } + int glyphs() { return utf8_strlen(str); } + bool empty() { return !str[0]; } + + // Quick hash to detect change (e.g., to avoid expensive drawing) + typedef IF::type hash_t; + hash_t hash() const { + const int sz = length(); + #if ENABLED(DJB2_HASH) + hash_t hval = 5381; + for (int i = 0; i < sz; i++) hval += (hval << 5) + str[i]; // = hval * 33 + c + #else + hash_t hval = hash_t(sz); + for (int i = 0; i < sz; i++) hval = ((hval << 1) | (hval >> 15)) ^ str[i]; // ROL, XOR + #endif + return hval; + } + + void copyto(char * const dst) const { strcpy(dst, str); } + void copyto(char * const dst, int len) const { strlcpy(dst, str, len + 1); } + + MString& clear() { return set(); } + MString& eol() { return append('\n'); } + MString& trunc(const int &i) { if (i <= SIZE) str[i] = '\0'; debug(F("trunc")); return *this; } + MString& ltrim() { char *s = str; while (*s == ' ') ++s; if (s != str) strcpy(str, s); return *this; } + MString& rtrim() { int s = length(); while (s && str[s - 1] == ' ') --s; str[s] = '\0'; return *this; } + MString& trim() { return rtrim().ltrim(); } + + // Truncate on a Unicode boundary + MString& utrunc(const int &n=SIZE) { + const int sz = length(); + if (sz && n <= sz) + for (int i = n; i >= 0; i--) if (START_OF_UTF8_CHAR(str[i])) { str[i] = '\0'; break; } + debug(F("utrunc")); + return *this; + } + +}; + +#pragma GCC diagnostic pop + +// Temporary inline string typically used to compose a G-code command +#ifndef TS_SIZE + #define TS_SIZE 63 +#endif +typedef MString TString; +#define TS(V...) TString(V) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 05a713e435..81a1754d5e 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -64,6 +64,9 @@ typedef const char Language_Str[]; #if NUM_LANGUAGES > 1 #define HAS_MULTI_LANGUAGE 1 + #if HAS_MARLINUI_MENU + #define HAS_MENU_MULTI_LANGUAGE 1 + #endif #define GET_TEXT(MSG) ( \ ui.language == 4 ? GET_LANG(LCD_LANGUAGE_5)::MSG : \ ui.language == 3 ? GET_LANG(LCD_LANGUAGE_4)::MSG : \ @@ -88,6 +91,7 @@ typedef const char Language_Str[]; #define LANG_CHARSIZE GET_TEXT(CHARSIZE) #define USE_WIDE_GLYPH (LANG_CHARSIZE > 2) +// The final "\0" is added invisibly by the compiler #define MSG_1_LINE(A) A "\0" "\0" #define MSG_2_LINE(A,B) A "\0" B "\0" #define MSG_3_LINE(A,B,C) A "\0" B "\0" C diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 727b191d04..852cfc77f6 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -27,7 +27,10 @@ #include "../feature/ethernet.h" #endif -uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE; +#include // dtostrf + +// Echo commands to the terminal by default in dev mode +uint8_t marlin_debug_flags = TERN(MARLIN_DEV_MODE, MARLIN_DEBUG_ECHO, MARLIN_DEBUG_NONE); // Commonly-used strings in serial output PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); @@ -68,31 +71,48 @@ MAP(_N_LBL, LOGICAL_AXIS_NAMES); MAP(_SP_N_LBL, LOGICAL_AXIS_NAMES); #endif -void serial_print_P(PGM_P str) { - while (const char c = pgm_read_byte(str++)) SERIAL_CHAR(c); +// Specializations for float, p_float_t, w_float_t +template <> void SERIAL_ECHO(const float f) { SERIAL_IMPL.print(f, SERIAL_FLOAT_PRECISION); } +template <> void SERIAL_ECHO(const p_float_t pf) { SERIAL_IMPL.print(pf.value, pf.prec); } +template <> void SERIAL_ECHO(const w_float_t wf) { char f1[20]; SERIAL_IMPL.print(dtostrf(wf.value, wf.width, wf.prec, f1)); } + +// Specializations for F-string +template <> void SERIAL_ECHO(FSTR_P const fstr) { SERIAL_ECHO_P(FTOP(fstr)); } +template <> void SERIAL_ECHOLN(FSTR_P const fstr) { SERIAL_ECHOLN_P(FTOP(fstr)); } + +void SERIAL_CHAR(char a) { SERIAL_IMPL.write(a); } +void SERIAL_EOL() { SERIAL_CHAR('\n'); } + +void SERIAL_ECHO(serial_char_t x) { SERIAL_IMPL.write(x.c); } + +void SERIAL_FLUSH() { SERIAL_IMPL.flush(); } +void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); } + +void SERIAL_ECHO_P(PGM_P pstr) { + while (const char c = pgm_read_byte(pstr++)) SERIAL_CHAR(c); } +void SERIAL_ECHOLN_P(PGM_P pstr) { SERIAL_ECHO_P(pstr); SERIAL_EOL(); } -void serial_echo_start() { serial_print(F("echo:")); } -void serial_error_start() { serial_print(F("Error:")); } +void SERIAL_ECHO_START() { SERIAL_ECHO(F("echo:")); } +void SERIAL_ERROR_START() { SERIAL_ECHO(F("Error:")); } +void SERIAL_WARN_START() { SERIAL_ECHO(F("Warning:")); } -void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); } +void SERIAL_ECHO_SP(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); } -void serial_offset(const_float_t v, const uint8_t sp/*=0*/) { +void serial_offset(const float v, const uint8_t sp/*=0*/) { if (v == 0 && sp == 1) SERIAL_CHAR(' '); else if (v > 0 || (v == 0 && sp == 2)) SERIAL_CHAR('+'); - SERIAL_DECIMAL(v); + SERIAL_ECHO(v); } -void serial_ternary(const bool onoff, FSTR_P const pre, FSTR_P const on, FSTR_P const off, FSTR_P const post/*=nullptr*/) { - if (pre) serial_print(pre); - serial_print(onoff ? on : off); - if (post) serial_print(post); +void serial_ternary(FSTR_P const pre, const bool onoff, FSTR_P const on, FSTR_P const off, FSTR_P const post/*=nullptr*/) { + if (pre) SERIAL_ECHO(pre); + if (onoff && on) SERIAL_ECHO(on); + if (!onoff && off) SERIAL_ECHO(off); + if (post) SERIAL_ECHO(post); } -void serialprint_onoff(const bool onoff) { serial_print(onoff ? F(STR_ON) : F(STR_OFF)); } -void serialprintln_onoff(const bool onoff) { serialprint_onoff(onoff); SERIAL_EOL(); } -void serialprint_truefalse(const bool tf) { serial_print(tf ? F("true") : F("false")); } void print_bin(uint16_t val) { for (uint8_t i = 16; i--;) { @@ -101,10 +121,26 @@ void print_bin(uint16_t val) { } } -void print_pos(NUM_AXIS_ARGS(const_float_t), FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) { - if (prefix) serial_print(prefix); - SERIAL_ECHOPGM_P( - LIST_N(DOUBLE(NUM_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k, SP_U_STR, u, SP_V_STR, v, SP_W_STR, w) - ); - if (suffix) serial_print(suffix); else SERIAL_EOL(); +void _print_xyz(NUM_AXIS_ARGS_(const float) FSTR_P const prefix) { + if (prefix) SERIAL_ECHO(prefix); + #if NUM_AXES + SERIAL_ECHOPGM_P(NUM_AXIS_PAIRED_LIST( + SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, + SP_I_STR, i, SP_J_STR, j, SP_K_STR, k, + SP_U_STR, u, SP_V_STR, v, SP_W_STR, w + )); + #endif +} + +void print_xyz(NUM_AXIS_ARGS_(const float) FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) { + _print_xyz(NUM_AXIS_LIST_(x, y, z, i, j, k, u, v, w) prefix); + if (suffix) SERIAL_ECHO(suffix); else SERIAL_EOL(); +} + +void print_xyze(LOGICAL_AXIS_ARGS_(const float) FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) { + _print_xyz(NUM_AXIS_LIST_(x, y, z, i, j, k, u, v, w) prefix); + #if HAS_EXTRUDERS + SERIAL_ECHOPGM_P(SP_E_STR, e); + #endif + if (suffix) SERIAL_ECHO(suffix); else SERIAL_EOL(); } diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index c19bc08783..6c73d72a22 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -33,19 +33,14 @@ // enum MarlinDebugFlags : uint8_t { MARLIN_DEBUG_NONE = 0, - MARLIN_DEBUG_ECHO = _BV(0), ///< Echo commands in order as they are processed - MARLIN_DEBUG_INFO = _BV(1), ///< Print messages for code that has debug output - MARLIN_DEBUG_ERRORS = _BV(2), ///< Not implemented - MARLIN_DEBUG_DRYRUN = _BV(3), ///< Ignore temperature setting and E movement commands - MARLIN_DEBUG_COMMUNICATION = _BV(4), ///< Not implemented - #if ENABLED(DEBUG_LEVELING_FEATURE) - MARLIN_DEBUG_LEVELING = _BV(5), ///< Print detailed output for homing and leveling - MARLIN_DEBUG_MESH_ADJUST = _BV(6), ///< UBL bed leveling - #else - MARLIN_DEBUG_LEVELING = 0, - MARLIN_DEBUG_MESH_ADJUST = 0, - #endif - MARLIN_DEBUG_ALL = 0xFF + MARLIN_DEBUG_ECHO = TERN0(DEBUG_FLAGS_GCODE, _BV(0)), //!< Echo commands in order as they are processed + MARLIN_DEBUG_INFO = TERN0(DEBUG_FLAGS_GCODE, _BV(1)), //!< Print messages for code that has debug output + MARLIN_DEBUG_ERRORS = TERN0(DEBUG_FLAGS_GCODE, _BV(2)), //!< Not implemented + MARLIN_DEBUG_DRYRUN = _BV(3), //!< Ignore temperature setting and E movement commands + MARLIN_DEBUG_COMMUNICATION = TERN0(DEBUG_FLAGS_GCODE, _BV(4)), //!< Not implemented + MARLIN_DEBUG_LEVELING = TERN0(DEBUG_LEVELING_FEATURE, _BV(5)), //!< Print detailed output for homing and leveling + MARLIN_DEBUG_MESH_ADJUST = TERN0(DEBUG_LEVELING_FEATURE, _BV(6)), //!< UBL bed leveling + MARLIN_DEBUG_ALL = MARLIN_DEBUG_ECHO|MARLIN_DEBUG_INFO|MARLIN_DEBUG_ERRORS|MARLIN_DEBUG_COMMUNICATION|MARLIN_DEBUG_LEVELING|MARLIN_DEBUG_MESH_ADJUST }; extern uint8_t marlin_debug_flags; @@ -125,8 +120,6 @@ extern uint8_t marlin_debug_flags; #define SERIAL_IMPL SERIAL_LEAF_1 #endif -#define SERIAL_OUT(WHAT, V...) (void)SERIAL_IMPL.WHAT(V) - #define PORT_REDIRECT(p) _PORT_REDIRECT(1,p) #define PORT_RESTORE() _PORT_RESTORE(1) #define SERIAL_PORTMASK(P) SerialMask::from(P) @@ -134,215 +127,180 @@ extern uint8_t marlin_debug_flags; // // SERIAL_CHAR - Print one or more individual chars // -inline void SERIAL_CHAR(char a) { SERIAL_IMPL.write(a); } +void SERIAL_CHAR(char a); template void SERIAL_CHAR(char a, Args ... args) { SERIAL_IMPL.write(a); SERIAL_CHAR(args ...); } /** - * SERIAL_ECHO - Print a single string or value. + * SERIAL_ECHO / SERIAL_ECHOLN - Print a single string or value. * Any numeric parameter (including char) is printed as a base-10 number. * A string pointer or literal will be output as a string. * * NOTE: Use SERIAL_CHAR to print char as a single character. */ -template -void SERIAL_ECHO(T x) { SERIAL_IMPL.print(x); } +template void SERIAL_ECHO(T x) { SERIAL_IMPL.print(x); } +template void SERIAL_ECHOLN(T x) { SERIAL_IMPL.println(x); } // Wrapper for ECHO commands to interpret a char -typedef struct SerialChar { char c; SerialChar(char n) : c(n) { } } serial_char_t; -inline void SERIAL_ECHO(serial_char_t x) { SERIAL_IMPL.write(x.c); } -#define AS_CHAR(C) serial_char_t(C) -#define AS_DIGIT(C) AS_CHAR('0' + (C)) +void SERIAL_ECHO(serial_char_t x); +#define AS_DIGIT(n) C('0' + (n)) -template -void SERIAL_ECHOLN(T x) { SERIAL_IMPL.println(x); } - -// SERIAL_PRINT works like SERIAL_ECHO but also takes the numeric base -template -void SERIAL_PRINT(T x, U y) { SERIAL_IMPL.print(x, y); } - -template -void SERIAL_PRINTLN(T x, PrintBase y) { SERIAL_IMPL.println(x, y); } +// Print an integer with a numeric base such as PrintBase::Hex +template void SERIAL_PRINT(T x, PrintBase y) { SERIAL_IMPL.print(x, y); } +template void SERIAL_PRINTLN(T x, PrintBase y) { SERIAL_IMPL.println(x, y); } // Flush the serial port -inline void SERIAL_FLUSH() { SERIAL_IMPL.flush(); } -inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); } +void SERIAL_FLUSH(); +void SERIAL_FLUSHTX(); -// Serial echo and error prefixes -#define SERIAL_ECHO_START() serial_echo_start() -#define SERIAL_ERROR_START() serial_error_start() +// Start an echo: or error: output +void SERIAL_ECHO_START(); +void SERIAL_ERROR_START(); +void SERIAL_WARN_START(); // Serial end-of-line -#define SERIAL_EOL() SERIAL_CHAR('\n') +void SERIAL_EOL(); // Print a single PROGMEM, PGM_P, or PSTR() string. -void serial_print_P(PGM_P str); -inline void serial_println_P(PGM_P str) { serial_print_P(str); SERIAL_EOL(); } +void SERIAL_ECHO_P(PGM_P pstr); +void SERIAL_ECHOLN_P(PGM_P pstr); -// Print a single FSTR_P, F(), or FPSTR() string. -inline void serial_print(FSTR_P const fstr) { serial_print_P(FTOP(fstr)); } -inline void serial_println(FSTR_P const fstr) { serial_println_P(FTOP(fstr)); } +// Specializations for float, p_float_t, and w_float_t +template<> void SERIAL_ECHO(const float f); +template<> void SERIAL_ECHO(const p_float_t pf); +template<> void SERIAL_ECHO(const w_float_t wf); + +// Specializations for F-string +template<> void SERIAL_ECHO(FSTR_P const fstr); +template<> void SERIAL_ECHOLN(FSTR_P const fstr); + +// Print any number of items with arbitrary types (except loose PROGMEM strings) +template +void SERIAL_ECHO(T arg1, Args ... args) { SERIAL_ECHO(arg1); SERIAL_ECHO(args ...); } +template +void SERIAL_ECHOLN(T arg1, Args ... args) { SERIAL_ECHO(arg1); SERIAL_ECHO(args ...); SERIAL_EOL(); } // -// SERIAL_ECHOPGM... macros are used to output string-value pairs. +// SERIAL_ECHOPGM... macros are used to output string-value pairs, wrapping +// all the odd loose string elements as PROGMEM strings. // -// Print up to 20 pairs of values. Odd elements must be literal strings. +// Print pairs of values. Odd elements must be literal strings. #define __SEP_N(N,V...) _SEP_##N(V) #define _SEP_N(N,V...) __SEP_N(N,V) #define _SEP_N_REF() _SEP_N -#define _SEP_1(s) serial_print(F(s)); -#define _SEP_2(s,v) serial_echopair(F(s),v); +#define _SEP_1(s) SERIAL_ECHO(F(s)); +#define _SEP_2(s,v) SERIAL_ECHO(F(s),v); #define _SEP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SEP_N_REF)()(TWO_ARGS(V),V); #define SERIAL_ECHOPGM(V...) do{ EVAL(_SEP_N(TWO_ARGS(V),V)); }while(0) -// Print up to 20 pairs of values followed by newline. Odd elements must be literal strings. +// Print pairs of values followed by newline. Odd elements must be literal strings. #define __SELP_N(N,V...) _SELP_##N(V) #define _SELP_N(N,V...) __SELP_N(N,V) #define _SELP_N_REF() _SELP_N -#define _SELP_1(s) serial_print(F(s "\n")); -#define _SELP_2(s,v) serial_echolnpair(F(s),v); +#define _SELP_1(s) SERIAL_ECHO(F(s "\n")); +#define _SELP_2(s,v) SERIAL_ECHOLN(F(s),v); #define _SELP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SELP_N_REF)()(TWO_ARGS(V),V); #define SERIAL_ECHOLNPGM(V...) do{ EVAL(_SELP_N(TWO_ARGS(V),V)); }while(0) -// Print up to 20 pairs of values. Odd elements must be PSTR pointers. +// Print pairs of values. Odd elements must be PSTR pointers. #define __SEP_N_P(N,V...) _SEP_##N##_P(V) #define _SEP_N_P(N,V...) __SEP_N_P(N,V) #define _SEP_N_P_REF() _SEP_N_P -#define _SEP_1_P(p) serial_print_P(p); -#define _SEP_2_P(p,v) serial_echopair_P(p,v); +#define _SEP_1_P(p) SERIAL_ECHO(FPSTR(p)); +#define _SEP_2_P(p,v) SERIAL_ECHO(FPSTR(p),v); #define _SEP_3_P(p,v,V...) _SEP_2_P(p,v); DEFER2(_SEP_N_P_REF)()(TWO_ARGS(V),V); #define SERIAL_ECHOPGM_P(V...) do{ EVAL(_SEP_N_P(TWO_ARGS(V),V)); }while(0) -// Print up to 20 pairs of values followed by newline. Odd elements must be PSTR pointers. +// Print pairs of values followed by newline. Odd elements must be PSTR pointers. #define __SELP_N_P(N,V...) _SELP_##N##_P(V) #define _SELP_N_P(N,V...) __SELP_N_P(N,V) #define _SELP_N_P_REF() _SELP_N_P -#define _SELP_1_P(p) serial_println_P(p) -#define _SELP_2_P(p,v) serial_echolnpair_P(p,v) +#define _SELP_1_P(p) SERIAL_ECHOLN(FPSTR(p)); +#define _SELP_2_P(p,v) SERIAL_ECHOLN(FPSTR(p),v); #define _SELP_3_P(p,v,V...) { _SEP_2_P(p,v); DEFER2(_SELP_N_P_REF)()(TWO_ARGS(V),V); } #define SERIAL_ECHOLNPGM_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0) -// Print up to 20 pairs of values. Odd elements must be FSTR_P, F(), or FPSTR(). -#define __SEP_N_F(N,V...) _SEP_##N##_F(V) -#define _SEP_N_F(N,V...) __SEP_N_F(N,V) -#define _SEP_N_F_REF() _SEP_N_F -#define _SEP_1_F(p) serial_print(p); -#define _SEP_2_F(p,v) serial_echopair(p,v); -#define _SEP_3_F(p,v,V...) _SEP_2_F(p,v); DEFER2(_SEP_N_F_REF)()(TWO_ARGS(V),V); -#define SERIAL_ECHOF(V...) do{ EVAL(_SEP_N_F(TWO_ARGS(V),V)); }while(0) +#define SERIAL_ECHO_MSG(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0) +#define SERIAL_ERROR_MSG(V...) do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(V); }while(0) +#define SERIAL_WARN_MSG(V...) do{ SERIAL_WARN_START(); SERIAL_ECHOLNPGM(V); }while(0) -// Print up to 20 pairs of values followed by newline. Odd elements must be FSTR_P, F(), or FPSTR(). -#define __SELP_N_F(N,V...) _SELP_##N##_F(V) -#define _SELP_N_F(N,V...) __SELP_N_F(N,V) -#define _SELP_N_F_REF() _SELP_N_F -#define _SELP_1_F(p) serial_println(p) -#define _SELP_2_F(p,v) serial_echolnpair(p,v) -#define _SELP_3_F(p,v,V...) { _SEP_2_F(p,v); DEFER2(_SELP_N_F_REF)()(TWO_ARGS(V),V); } -#define SERIAL_ECHOLNF(V...) do{ EVAL(_SELP_N_F(TWO_ARGS(V),V)); }while(0) +// Print a prefix, conditional string, and suffix +void serial_ternary(FSTR_P const pre, const bool onoff, FSTR_P const on, FSTR_P const off, FSTR_P const post=nullptr); +// Shorthand to put loose strings in PROGMEM +#define SERIAL_ECHO_TERNARY(TF, PRE, ON, OFF, POST) serial_ternary(F(PRE), TF, F(ON), F(OFF), F(POST)) -#ifdef AllowDifferentTypeInList +// Print up to 255 spaces +void SERIAL_ECHO_SP(uint8_t count); - inline void SERIAL_ECHOLIST_IMPL() {} - template - void SERIAL_ECHOLIST_IMPL(T && t) { SERIAL_IMPL.print(t); } +inline FSTR_P const ON_OFF(const bool onoff) { return onoff ? F("ON") : F("OFF"); } +inline FSTR_P const TRUE_FALSE(const bool tf) { return tf ? F("true") : F("false"); } - template - void SERIAL_ECHOLIST_IMPL(T && t, Args && ... args) { - SERIAL_IMPL.print(t); - serial_print(F(", ")); - SERIAL_ECHOLIST_IMPL(args...); - } - - template - void SERIAL_ECHOLIST(FSTR_P const str, Args && ... args) { - SERIAL_IMPL.print(FTOP(str)); - SERIAL_ECHOLIST_IMPL(args...); - } - -#else // Optimization if the listed type are all the same (seems to be the case in the codebase so use that instead) - - template - void SERIAL_ECHOLIST(FSTR_P const fstr, Args && ... args) { - serial_print(fstr); - typename Private::first_type_of::type values[] = { args... }; - constexpr size_t argsSize = sizeof...(args); - for (size_t i = 0; i < argsSize; i++) { - if (i) serial_print(F(", ")); - SERIAL_IMPL.print(values[i]); - } - } - -#endif - -// SERIAL_ECHO_F prints a floating point value with optional precision -inline void SERIAL_ECHO_F(EnsureDouble x, int digit=2) { SERIAL_IMPL.print(x, digit); } - -#define SERIAL_ECHOPAIR_F_P(P,V...) do{ serial_print_P(P); SERIAL_ECHO_F(V); }while(0) -#define SERIAL_ECHOLNPAIR_F_P(P,V...) do{ SERIAL_ECHOPAIR_F_P(P,V); SERIAL_EOL(); }while(0) - -#define SERIAL_ECHOPAIR_F_F(S,V...) do{ serial_print(S); SERIAL_ECHO_F(V); }while(0) -#define SERIAL_ECHOLNPAIR_F_F(S,V...) do{ SERIAL_ECHOPAIR_F_F(S,V); SERIAL_EOL(); }while(0) - -#define SERIAL_ECHOPAIR_F(S,V...) SERIAL_ECHOPAIR_F_F(F(S),V) -#define SERIAL_ECHOLNPAIR_F(V...) do{ SERIAL_ECHOPAIR_F(V); SERIAL_EOL(); }while(0) - -#define SERIAL_ECHO_MSG(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0) -#define SERIAL_ERROR_MSG(V...) do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(V); }while(0) - -#define SERIAL_ECHO_SP(C) serial_spaces(C) - -#define SERIAL_ECHO_TERNARY(TF, PRE, ON, OFF, POST) serial_ternary(TF, F(PRE), F(ON), F(OFF), F(POST)) - -#if SERIAL_FLOAT_PRECISION - #define SERIAL_DECIMAL(V) SERIAL_PRINT(V, SERIAL_FLOAT_PRECISION) -#else - #define SERIAL_DECIMAL(V) SERIAL_ECHO(V) -#endif - -// -// Functions for serial printing from PROGMEM. (Saves loads of SRAM.) -// -inline void serial_echopair_P(PGM_P const pstr, serial_char_t v) { serial_print_P(pstr); SERIAL_CHAR(v.c); } -inline void serial_echopair_P(PGM_P const pstr, float v) { serial_print_P(pstr); SERIAL_DECIMAL(v); } -inline void serial_echopair_P(PGM_P const pstr, double v) { serial_print_P(pstr); SERIAL_DECIMAL(v); } -//inline void serial_echopair_P(PGM_P const pstr, const char *v) { serial_print_P(pstr); SERIAL_ECHO(v); } -inline void serial_echopair_P(PGM_P const pstr, FSTR_P v) { serial_print_P(pstr); SERIAL_ECHOF(v); } - -// Default implementation for types without a specialization. Handles integers. -template -inline void serial_echopair_P(PGM_P const pstr, T v) { serial_print_P(pstr); SERIAL_ECHO(v); } - -// Add a newline. -template -inline void serial_echolnpair_P(PGM_P const pstr, T v) { serial_echopair_P(pstr, v); SERIAL_EOL(); } - -// Catch-all for __FlashStringHelper * -template -inline void serial_echopair(FSTR_P const fstr, T v) { serial_echopair_P(FTOP(fstr), v); } - -// Add a newline to the serial output -template -inline void serial_echolnpair(FSTR_P const fstr, T v) { serial_echolnpair_P(FTOP(fstr), v); } - -void serial_echo_start(); -void serial_error_start(); -void serial_ternary(const bool onoff, FSTR_P const pre, FSTR_P const on, FSTR_P const off, FSTR_P const post=nullptr); -void serialprint_onoff(const bool onoff); -void serialprintln_onoff(const bool onoff); -void serialprint_truefalse(const bool tf); -void serial_spaces(uint8_t count); -void serial_offset(const_float_t v, const uint8_t sp=0); // For v==0 draw space (sp==1) or plus (sp==2) +void serial_offset(const float v, const uint8_t sp=0); // For v==0 draw space (sp==1) or plus (sp==2) void print_bin(const uint16_t val); -void print_pos(NUM_AXIS_ARGS(const_float_t), FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr); -inline void print_pos(const xyz_pos_t &xyz, FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr) { - print_pos(NUM_AXIS_ELEM(xyz), prefix, suffix); +void print_xyz(NUM_AXIS_ARGS_(const float) FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr); +inline void print_xyz(const xyz_pos_t &xyz, FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr) { + print_xyz(NUM_AXIS_ELEM_(xyz) prefix, suffix); } -#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) +void print_xyze(LOGICAL_AXIS_ARGS_(const float) FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr); +inline void print_xyze(const xyze_pos_t &xyze, FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr) { + print_xyze(LOGICAL_AXIS_ELEM_LC_(xyze) prefix, suffix); +} + +#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(VAR, F(" " STRINGIFY(VAR) "="), F(" : " SUFFIX "\n")); }while(0) +#define SERIAL_XYZ(PREFIX,V...) do { print_xyz(V, F(PREFIX)); }while(0) + +/** + * Extended string that can echo itself to serial + */ +template +class SString : public MString { +public: + typedef MString super; + using super::str; + using super::debug; + + SString() : super() {} + + template + SString(T arg1, Args... more) : super(arg1, more...) {} + + SString& set() { super::set(); return *this; } + + template + SString& setf_P(PGM_P const pfmt, Args... more) { super::setf_P(pfmt, more...); return *this; } + + template + SString& setf(const char *fmt, Args... more) { super::setf(fmt, more...); return *this; } + + template + SString& setf(FSTR_P const ffmt, Args... more) { super::setf(ffmt, more...); return *this; } + + template + SString& set(const T &v) { super::set(v); return *this; } + + template + SString& append(const T &v) { super::append(v); return *this; } + + template + SString& set(T arg1, Args... more) { set(arg1).append(more...); return *this; } + + template + SString& append(T arg1, Args... more) { append(arg1).append(more...); return *this; } + + SString& clear() { set(); return *this; } + SString& eol() { append('\n'); return *this; } + SString& trunc(const int &i) { super::trunc(i); return *this; } + + // Extended with methods to print to serial + SString& echo() { SERIAL_ECHO(str); return *this; } + SString& echoln() { SERIAL_ECHOLN(str); return *this; } +}; + +#define TSS(V...) SString<>(V) // // Commonly-used strings in serial output diff --git a/Marlin/src/core/serial_base.h b/Marlin/src/core/serial_base.h index a5abd67d87..07bed55b35 100644 --- a/Marlin/src/core/serial_base.h +++ b/Marlin/src/core/serial_base.h @@ -23,6 +23,8 @@ #include "../inc/MarlinConfigPre.h" +#include // for size_t + #if ENABLED(EMERGENCY_PARSER) #include "../feature/e_parser.h" #endif @@ -77,7 +79,7 @@ struct EnsureDouble { operator double() { return a; } // If the compiler breaks on ambiguity here, it's likely because print(X, base) is called with X not a double/float, and // a base that's not a PrintBase value. This code is made to detect the error. You MUST set a base explicitly like this: - // SERIAL_PRINT(v, PrintBase::Hex) + //SERIAL_PRINT(v, PrintBase::Hex) EnsureDouble(double a) : a(a) {} EnsureDouble(float a) : a(a) {} }; @@ -167,7 +169,6 @@ struct SerialBase { FORCE_INLINE void print(unsigned int c, PrintBase base) { printNumber_unsigned(c, base); } FORCE_INLINE void print(unsigned long c, PrintBase base) { printNumber_unsigned(c, base); } - void print(EnsureDouble c, int digits) { printFloat(c, digits); } // Forward the call to the former's method @@ -178,7 +179,7 @@ struct SerialBase { void print(T c) { print(c, PrintBase::Dec); } void print(float c) { print(c, 2); } - void print(double c) { print(c, 2); } + void print(double c) { print(c, 2); } void println(char *s) { print(s); println(); } void println(const char *s) { print(s); println(); } @@ -219,7 +220,7 @@ struct SerialBase { // On non 2-complement CPU, there would be no possible representation for 2147483648. write('-'); } - printNumber_unsigned((uint_fixed_print_t)n , base); + printNumber_unsigned((uint_fixed_print_t)n, base); } // Print a decimal number @@ -227,12 +228,12 @@ struct SerialBase { // Handle negative numbers if (number < 0.0) { write('-'); - number = -number; + number *= -1; } // Round correctly so that print(1.999, 2) prints as "2.00" double rounding = 0.5; - LOOP_L_N(i, digits) rounding *= 0.1; + for (uint8_t i = 0; i < digits; ++i) rounding *= 0.1; number += rounding; // Extract the integer part of the number and print it diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index 65c553c702..06efce1dc5 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -179,7 +179,7 @@ struct RuntimeSerial : public SerialBase< RuntimeSerial >, public Seria // Append Hookable for this class SerialFeature features(serial_index_t index) const { return SerialFeature::Hookable | CALL_IF_EXISTS(SerialFeature, static_cast(this), features, index); } - void setHook(WriteHook writeHook = 0, EndOfMessageHook eofHook = 0, void * userPointer = 0) { + void setHook(WriteHook writeHook=0, EndOfMessageHook eofHook=0, void * userPointer=0) { // Order is important here as serial code can be called inside interrupts // When setting a hook, the user pointer must be set first so if writeHook is called as soon as it's set, it'll be valid if (userPointer) this->userPointer = userPointer; @@ -292,7 +292,7 @@ struct MultiSerial : public SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) #define _S_REFS(N) Serial##N##T & serial##N, #define _S_INIT(N) ,serial##N (serial##N) - MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask = ALL, const bool e = false) + MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask=ALL, const bool e=false) : BaseClassT(e), portMask(mask) REPEAT(NUM_SERIAL, _S_INIT) {} }; diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index c9bb7d8c30..0881bc47a1 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -31,50 +31,137 @@ // // typename IF<(MYOPT==12), int, float>::type myvar; // -template -struct IF { typedef R type; }; -template -struct IF { typedef L type; }; +template struct IF { typedef R type; }; +template struct IF { typedef L type; }; -#define 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 ALL_AXIS_NAMES X, X2, Y, Y2, Z, Z2, Z3, Z4, I, J, K, U, V, W, E0, E1, E2, E3, E4, E5, E6, E7 -#define 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 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_ARGS_LC(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_ELEM_LC(O) NUM_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) +#define NUM_AXIS_DECL(T,V) NUM_AXIS_LIST(T X=V, T Y=V, T Z=V, T I=V, T J=V, T K=V, T U=V, T V=V, T W=V) +#define NUM_AXIS_DECL_LC(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_NAMES_LC NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w) +#define NUM_AXIS_CALL(G) do { NUM_AXIS_CODE(G(X_AXIS), G(Y_AXIS), G(Z_AXIS), G(I_AXIS), G(J_AXIS), G(K_AXIS), G(U_AXIS), G(V_AXIS), G(W_AXIS)); } while(0) +#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(N,V...) NUM_AXIS_GANG(V) GANG_ITEM_E(N) +#define LOGICAL_AXIS_CODE(N,V...) NUM_AXIS_CODE(V) CODE_ITEM_E(N) +#define LOGICAL_AXIS_LIST(N,V...) NUM_AXIS_LIST(V) LIST_ITEM_E(N) +#define LOGICAL_AXIS_LIST_1(V) NUM_AXIS_LIST_1(V) LIST_ITEM_E(V) +#define LOGICAL_AXIS_ARRAY(N,V...) { LOGICAL_AXIS_LIST(N,V) } #define LOGICAL_AXIS_ARRAY_1(V) { LOGICAL_AXIS_LIST_1(V) } -#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k, T u, T v, T w) -#define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) -#define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V, T u=V, T v=V, T w=V) -#define LOGICAL_AXIS_NAMES LOGICAL_AXIS_LIST(E, X, Y, Z, I, J, K, U, V, W) -#define LOGICAL_AXIS_MAP(F) MAP(F, LOGICAL_AXIS_NAMES) -#define STR_AXES_LOGICAL LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W) +#define LOGICAL_AXIS_ARGS(T) LOGICAL_AXIS_LIST(T E, T X, T Y, T Z, T I, T J, T K, T U, T V, T W) +#define LOGICAL_AXIS_ARGS_LC(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_ELEM_LC(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) +#define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T E=V, T X=V, T Y=V, T Z=V, T I=V, T J=V, T K=V, T U=V, T V=V, T W=V) +#define LOGICAL_AXIS_DECL_LC(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V, T u=V, T v=V, T w=V) +#define LOGICAL_AXIS_NAMES LOGICAL_AXIS_LIST(E, X, Y, Z, I, J, K, U, V, W) +#define LOGICAL_AXIS_NAMES_LC LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w) +#define LOGICAL_AXIS_MAP(F) MAP(F, LOGICAL_AXIS_NAMES) +#define LOGICAL_AXIS_MAP_LC(F) MAP(F, LOGICAL_AXIS_NAMES_LC) +#define LOGICAL_AXIS_CALL(G) do { LOGICAL_AXIS_CODE(G(E_AXIS), G(X_AXIS), G(Y_AXIS), G(Z_AXIS), G(I_AXIS), G(J_AXIS), G(K_AXIS), G(U_AXIS), G(V_AXIS), G(W_AXIS)); } while(0) +#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) +#define NUM_AXIS_PAIRED_LIST(V...) LIST_N(DOUBLE(NUM_AXES), V) +#define LOGICAL_AXIS_PAIRED_LIST(EA,EB,V...) NUM_AXIS_PAIRED_LIST(V) LIST_ITEM_E(EA) LIST_ITEM_E(EB) + +#if NUM_AXES + #define NUM_AXES_SEP , + #define MAIN_AXIS_MAP(F) MAP(F, MAIN_AXIS_NAMES) + #define MAIN_AXIS_MAP_LC(F) MAP(F, MAIN_AXIS_NAMES_LC) + #define OPTARGS_NUM(T) , NUM_AXIS_ARGS_LC(T) + #define OPTARGS_LOGICAL(T) , LOGICAL_AXIS_ARGS_LC(T) +#else + #define NUM_AXES_SEP + #define MAIN_AXIS_MAP(F) + #define MAIN_AXIS_MAP_LC(F) + #define OPTARGS_NUM(T) + #define OPTARGS_LOGICAL(T) +#endif + +#define NUM_AXIS_GANG_(V...) NUM_AXIS_GANG(V) NUM_AXES_SEP +#define NUM_AXIS_LIST_(V...) NUM_AXIS_LIST(V) NUM_AXES_SEP +#define NUM_AXIS_LIST_1_(V...) NUM_AXIS_LIST_1(V) NUM_AXES_SEP +#define NUM_AXIS_ARGS_(T) NUM_AXIS_ARGS_LC(T) NUM_AXES_SEP +#define NUM_AXIS_ELEM_(T) NUM_AXIS_ELEM_LC(T) NUM_AXES_SEP +#define MAIN_AXIS_NAMES_ MAIN_AXIS_NAMES NUM_AXES_SEP +#define MAIN_AXIS_NAMES_LC_ MAIN_AXIS_NAMES_LC NUM_AXES_SEP + +#if LOGICAL_AXES + #define LOGICAL_AXES_SEP , +#else + #define LOGICAL_AXES_SEP +#endif + +#define LOGICAL_AXIS_GANG_(V...) LOGICAL_AXIS_GANG(V) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_LIST_(V...) LOGICAL_AXIS_LIST(V) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_LIST_1_(V...) LOGICAL_AXIS_LIST_1(V) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_ARGS_(T) LOGICAL_AXIS_ARGS_LC(T) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_ELEM_(T) LOGICAL_AXIS_ELEM(T) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_ELEM_LC_(T) LOGICAL_AXIS_ELEM_LC(T) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_NAMES_ LOGICAL_AXIS_NAMES LOGICAL_AXES_SEP +#define LOGICAL_AXIS_NAMES_LC_ LOGICAL_AXIS_NAMES_LC LOGICAL_AXES_SEP #define SECONDARY_AXIS_GANG(V...) GANG_N(SECONDARY_AXES, V) #define SECONDARY_AXIS_CODE(V...) CODE_N(SECONDARY_AXES, V) +#define SECONDARY_AXIS_LIST(V...) LIST_N(SECONDARY_AXES, V) +#if SECONDARY_AXES + #define SECONDARY_AXIS_NAMES SECONDARY_AXIS_LIST(I, J, K, U, V, W) + #define SECONDARY_AXIS_NAMES_LC SECONDARY_AXIS_LIST(i, j, k, u, v, w) + #define SECONDARY_AXIS_ARGS(T) SECONDARY_AXIS_LIST(T I, T J, T K, T U, T V, T W) + #define SECONDARY_AXIS_ARGS_LC(T) SECONDARY_AXIS_LIST(T i, T j, T k, T u, T v, T w) + #define SECONDARY_AXIS_MAP(F) MAP(F, SECONDARY_AXIS_NAMES) + #define SECONDARY_AXIS_MAP_LC(F) MAP(F, SECONDARY_AXIS_NAMES_LC) +#else + #define SECONDARY_AXIS_MAP(F) + #define SECONDARY_AXIS_MAP_LC(F) +#endif + +// Just the XY or XYZ elements +#if HAS_Z_AXIS + #define XYZ_COUNT 3 + #define XY_COUNT 2 +#elif HAS_Y_AXIS + #define XY_COUNT 2 +#elif HAS_X_AXIS + #define XY_COUNT 1 +#else + #define XY_COUNT 0 +#endif +#ifndef XYZ_COUNT + #define XYZ_COUNT XY_COUNT +#endif +#define XY_LIST(V...) LIST_N(XY_COUNT, V) +#define XY_ARRAY(V...) ARRAY_N(XY_COUNT, V) +#define XY_CODE(V...) CODE_N(XY_COUNT, V) +#define XY_GANG(V...) GANG_N(XY_COUNT, V) +#define XYZ_LIST(V...) LIST_N(XYZ_COUNT, V) +#define XYZ_ARRAY(V...) ARRAY_N(XYZ_COUNT, V) +#define XYZ_CODE(V...) CODE_N(XYZ_COUNT, V) +#define XYZ_GANG(V...) GANG_N(XYZ_COUNT, V) #if HAS_ROTATIONAL_AXES #define ROTATIONAL_AXIS_GANG(V...) GANG_N(ROTATIONAL_AXES, V) #endif #if HAS_EXTRUDERS - #define LIST_ITEM_E(N) , N - #define CODE_ITEM_E(N) ; N + #if NUM_AXES + #define LIST_ITEM_E(N) , N + #define CODE_ITEM_E(N) ; N + #else + #define LIST_ITEM_E(N) N + #define CODE_ITEM_E(N) N + #endif #define GANG_ITEM_E(N) N #else #define LIST_ITEM_E(N) @@ -82,154 +169,277 @@ struct IF { typedef L type; }; #define GANG_ITEM_E(N) #endif +// Emitters for code that only cares about XYZE and not IJKUVW +#define CARTES_COUNT TERN(HAS_EXTRUDERS, INCREMENT(XYZ_COUNT), XYZ_COUNT) +#define CARTES_LIST(x,y,z,e) XYZ_LIST(x,y,z) LIST_ITEM_E(e) +#define CARTES_PAIRED_LIST(V...) LIST_N(DOUBLE(CARTES_COUNT), V) +#define CARTES_ARRAY(x,y,z,e) { CARTES_LIST(x,y,z,e) } +#define CARTES_CODE(x,y,z,e) XYZ_CODE(x,y,z) CODE_ITEM_E(e) +#define CARTES_GANG(x,y,z,e) XYZ_GANG(x,y,z) GANG_ITEM_E(e) +#define CARTES_AXIS_NAMES CARTES_LIST(X,Y,Z,E) +#define CARTES_AXIS_NAMES_LC CARTES_LIST(x,y,z,e) +#define CARTES_MAP(F) MAP(F, CARTES_AXIS_NAMES) +#if CARTES_COUNT + #define CARTES_COMMA , +#else + #define CARTES_COMMA +#endif + #define AXIS_COLLISION(L) (AXIS4_NAME == L || AXIS5_NAME == L || AXIS6_NAME == L || AXIS7_NAME == L || AXIS8_NAME == L || AXIS9_NAME == L) -// General Flags for some number of states +// Helpers +#define _RECIP(N) ((N) ? 1.0f / static_cast(N) : 0.0f) +#define _ABS(N) ((N) < decltype(N)(0) ? -(N) : (N)) +#define _LS(N) T(uint32_t(N) << p) +#define _RS(N) T(uint32_t(N) >> p) +#define _LSE(N) N = T(uint32_t(N) << p) +#define _RSE(N) N = T(uint32_t(N) >> p) +#define FI FORCE_INLINE + +// Define types based on largest bit width stored value required +#define bits_t(W) typename IF<((W)> 32), uint64_t, typename IF<((W)> 16), uint32_t, typename IF<((W)>8), uint16_t, uint8_t>::type>::type>::type +#define uvalue_t(V) typename IF<((V)>65535), uint32_t, typename IF<((V)>255), uint16_t, uint8_t>::type>::type +#define value_t(V) typename IF<((V)>32767), int32_t, typename IF<((V)>127), int16_t, int8_t>::type>::type + +class BitProxy; + +// Define a template for a bit field of N bits, using the smallest type that can hold N bits +template 64)> +struct Flags; + +// Flag bits for <= 64 states template -struct Flags { - typedef typename IF<(N>8), uint16_t, uint8_t>::type bits_t; - typedef struct { bool b0:1, b1:1, b2:1, b3:1, b4:1, b5:1, b6:1, b7:1; } N8; - typedef struct { bool b0:1, b1:1, b2:1, b3:1, b4:1, b5:1, b6:1, b7:1, b8:1, b9:1, b10:1, b11:1, b12:1, b13:1, b14:1, b15:1; } N16; - union { - bits_t b; - typename IF<(N>8), N16, N8>::type flag; +struct Flags { + typedef bits_t(N) flagbits_t; + flagbits_t b; + + class BitProxy { + public: + BitProxy(flagbits_t& data, int bit) : data_(data), bit_(bit) {} + + BitProxy& operator=(const bool value) { + if (value) + data_ |= (flagbits_t(1) << bit_); + else + data_ &= ~(flagbits_t(1) << bit_); + return *this; + } + + operator bool() const { return bool(data_ & (flagbits_t(1) << bit_)); } + + private: + flagbits_t& data_; + uint8_t bit_; }; - void reset() { b = 0; } - void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } - void set(const int n) { b |= (bits_t)_BV(n); } - void clear(const int n) { b &= ~(bits_t)_BV(n); } - bool test(const int n) const { return TEST(b, n); } - 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); } + + FI void reset() { b = 0; } + FI void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } + FI void set(const int n) { b |= (flagbits_t(1) << n); } + FI void clear(const int n) { b &= ~(flagbits_t(1) << n); } + FI bool test(const int n) const { return bool(b & (flagbits_t(1) << n)); } + FI BitProxy operator[](const int n) { return BitProxy(b, n); } + FI bool operator[](const int n) const { return test(n); } + FI int size() const { return sizeof(b); } + FI operator bool() const { return b != 0; } + + FI Flags& operator|=(Flags &p) const { b |= p.b; return *this; } + FI Flags& operator&=(Flags &p) const { b &= p.b; return *this; } + FI Flags& operator^=(Flags &p) const { b ^= p.b; return *this; } + + FI Flags& operator|=(const flagbits_t &p) { b |= flagbits_t(p); return *this; } + FI Flags& operator&=(const flagbits_t &p) { b &= flagbits_t(p); return *this; } + FI Flags& operator^=(const flagbits_t &p) { b ^= flagbits_t(p); return *this; } + + FI Flags operator|(Flags &p) const { return Flags(b | p.b); } + FI Flags operator&(Flags &p) const { return Flags(b & p.b); } + FI Flags operator^(Flags &p) const { return Flags(b ^ p.b); } + FI Flags operator~() const { return Flags(~b); } + + FI flagbits_t operator|(const flagbits_t &p) const { return b | flagbits_t(p); } + FI flagbits_t operator&(const flagbits_t &p) const { return b & flagbits_t(p); } + FI flagbits_t operator^(const flagbits_t &p) const { return b ^ flagbits_t(p); } + +}; + +// Flag bits for more than 64 states +template +struct Flags { + uint8_t bitmask[(N+7)>>3]; + // Proxy class for handling bit assignment + class BitProxy { + public: + BitProxy(uint8_t data[], int n) : data_(data[n >> 3]), bit_(n & 7) {} + + // Assignment operator + BitProxy& operator=(const bool value) { + if (value) + data_ |= _BV(bit_); + else + data_ &= ~_BV(bit_); + return *this; + } + + // Conversion operator to bool + operator bool() const { return TEST(data_, bit_); } + + private: + uint8_t& data_; + uint8_t bit_; + }; + + FI void reset() { for (uint8_t b = 0; b < sizeof(bitmask); ++b) bitmask[b] = 0; } + FI void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } + FI void set(const int n) { bitmask[n >> 3] |= _BV(n & 7); } + FI void clear(const int n) { bitmask[n >> 3] &= ~_BV(n & 7); } + FI bool test(const int n) const { return TEST(bitmask[n >> 3], n & 7); } + FI BitProxy operator[](const int n) { return BitProxy(bitmask, n); } + FI bool operator[](const int n) const { return test(n); } + FI int size() const { return sizeof(bitmask); } + FI operator bool() const { for (uint8_t b : bitmask) if (b) return true; return false; } }; // Specialization for a single bool flag template<> -struct Flags<1> { +struct Flags<1, false> { bool b; - void reset() { b = false; } - void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } - void set(const int) { b = true; } - void clear(const int) { b = false; } - bool test(const int) const { return b; } - bool& operator[](const int) { return b; } - bool operator[](const int) const { return b; } - int size() const { return sizeof(b); } + FI void reset() { b = false; } + FI void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } + FI void set(const int) { b = true; } + FI void clear(const int) { b = false; } + FI bool test(const int) const { return b; } + FI bool& operator[](const int) { return b; } + FI bool operator[](const int) const { return b; } + FI int size() const { return sizeof(b); } + FI operator bool() const { return b; } }; typedef Flags<8> flags_8_t; typedef Flags<16> flags_16_t; // Flags for some axis states, with per-axis aliases xyzijkuvwe -typedef struct AxisFlags { +typedef struct { union { struct Flags flags; struct { bool LOGICAL_AXIS_LIST(e:1, x:1, y:1, z:1, i:1, j:1, k:1, u:1, v:1, w:1); }; }; - void reset() { flags.reset(); } - void set(const int n) { flags.set(n); } - void set(const int n, const bool onoff) { flags.set(n, onoff); } - void clear(const int n) { flags.clear(n); } - bool test(const int n) const { return flags.test(n); } - bool operator[](const int n) { return flags[n]; } - bool operator[](const int n) const { return flags[n]; } - int size() const { return sizeof(flags); } -} axis_flags_t; + FI void reset() { flags.reset(); } + FI void set(const int n) { flags.set(n); } + FI void set(const int n, const bool onoff) { flags.set(n, onoff); } + FI void clear(const int n) { flags.clear(n); } + FI bool test(const int n) const { return flags.test(n); } + FI bool operator[](const int n) { return flags[n]; } + FI bool operator[](const int n) const { return flags[n]; } + FI int size() const { return sizeof(flags); } + FI operator bool() const { return (bool)flags; } +} AxisFlags; // // Enumerated axis indices // // - X_AXIS, Y_AXIS, and Z_AXIS should be used for axes in Cartesian space // - A_AXIS, B_AXIS, and C_AXIS should be used for Steppers, corresponding to XYZ on Cartesians -// - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics +// - X_HEAD, Y_HEAD, and Z_HEAD should be used for axes on Core kinematics // enum AxisEnum : uint8_t { // Linear axes may be controlled directly or indirectly - NUM_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS, U_AXIS, V_AXIS, W_AXIS) + NUM_AXIS_LIST_(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS, U_AXIS, V_AXIS, W_AXIS) - // Extruder axes may be considered distinctly - #define _EN_ITEM(N) , E##N##_AXIS + #define _EN_ITEM(N) E##N##_AXIS, REPEAT(EXTRUDERS, _EN_ITEM) #undef _EN_ITEM // Core also keeps toolhead directions #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) - , X_HEAD, Y_HEAD, Z_HEAD + X_HEAD, Y_HEAD, Z_HEAD, #endif // Distinct axes, including all E and Core - , NUM_AXIS_ENUMS + NUM_AXIS_HEADS, // Most of the time we refer only to the single E_AXIS #if HAS_EXTRUDERS - , E_AXIS = E0_AXIS + E_AXIS = E0_AXIS, #endif // A, B, and C are for DELTA, SCARA, etc. - , A_AXIS = X_AXIS + #if HAS_X_AXIS + A_AXIS = X_AXIS, + #endif #if HAS_Y_AXIS - , B_AXIS = Y_AXIS + B_AXIS = Y_AXIS, #endif #if HAS_Z_AXIS - , C_AXIS = Z_AXIS + C_AXIS = Z_AXIS, #endif // To refer to all or none - , ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF + ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF }; -typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t; - // // Loop over axes // -#define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS) -#define LOOP_NUM_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, NUM_AXES) -#define LOOP_LOGICAL_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LOGICAL_AXES) -#define LOOP_DISTINCT_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, DISTINCT_AXES) -#define LOOP_DISTINCT_E(VAR) LOOP_L_N(VAR, DISTINCT_E) +#define LOOP_ABC(VAR) for (uint8_t VAR = A_AXIS; VAR <= C_AXIS; ++VAR) +#define LOOP_NUM_AXES(VAR) for (uint8_t VAR = 0; VAR < NUM_AXES; ++VAR) +#define LOOP_LOGICAL_AXES(VAR) for (uint8_t VAR = 0; VAR < LOGICAL_AXES; ++VAR) +#define LOOP_DISTINCT_AXES(VAR) for (uint8_t VAR = 0; VAR < DISTINCT_AXES; ++VAR) +#define LOOP_DISTINCT_E(VAR) for (uint8_t VAR = 0; VAR < DISTINCT_E; ++VAR) // -// feedRate_t is just a humble float +// feedRate_t is just a humble float that can represent mm/s or mm/min // typedef float feedRate_t; // // celsius_t is the native unit of temperature. Signed to handle a disconnected thermistor value (-14). -// For more resolition (e.g., for a chocolate printer) this may later be changed to Celsius x 100 +// For more resolution (e.g., for a chocolate printer) this may later be changed to Celsius x 100 // typedef uint16_t raw_adc_t; typedef int16_t celsius_t; typedef float celsius_float_t; -// -// On AVR pointers are only 2 bytes so use 'const float &' for 'const float' -// -#ifdef __AVR__ - typedef const float & const_float_t; -#else - typedef const float const_float_t; -#endif -typedef const_float_t const_feedRate_t; -typedef const_float_t const_celsius_float_t; +// Type large enough to count leveling grid points +typedef IF 255)), uint16_t, uint8_t>::type grid_count_t; // Conversion macros #define MMM_TO_MMS(MM_M) feedRate_t(static_cast(MM_M) / 60.0f) #define MMS_TO_MMM(MM_S) (static_cast(MM_S) * 60.0f) +// Packaged character for C macro and other usage +typedef struct SerialChar { char c; SerialChar(const char n) : c(n) { } } serial_char_t; +#define C(c) serial_char_t(c) + +// Packaged types: float with precision and/or width; a repeated space/character +typedef struct WFloat { float value; char width; char prec; + WFloat(float v, char w, char p) : value(v), width(w), prec(p) {} + } w_float_t; +typedef struct PFloat { float value; char prec; + PFloat(float v, char p) : value(v), prec(p) {} + } p_float_t; +typedef struct RepChr { char asc; int8_t count; + RepChr(char a, uint8_t c) : asc(a), count(c) {} + } repchr_t; +typedef struct Spaces { int8_t count; + Spaces(uint8_t c) : count(c) {} + } spaces_t; + +#ifdef __AVR__ + typedef w_float_t w_double_t; + typedef p_float_t p_double_t; +#else + typedef struct WDouble { double value; char width; char prec; + WDouble(double v, char w, char p) : value(v), width(w), prec(p) {} + } w_double_t; + typedef struct PDouble { double value; char prec; + PDouble(double v, char p) : value(v), prec(p) {} + } p_double_t; +#endif + // // Coordinates structures for XY, XYZ, XYZE... // -// Helpers -#define _RECIP(N) ((N) ? 1.0f / static_cast(N) : 0.0f) -#define _ABS(N) ((N) < 0 ? -(N) : (N)) -#define _LS(N) (N = (T)(uint32_t(N) << v)) -#define _RS(N) (N = (T)(uint32_t(N) >> v)) -#define FI FORCE_INLINE - // Forward declarations template struct XYval; template struct XYZval; @@ -303,184 +513,207 @@ typedef ab_float_t ab_pos_t; typedef abc_float_t abc_pos_t; typedef abce_float_t abce_pos_t; -// External conversion methods +// External conversion methods (motion.h) void toLogical(xy_pos_t &raw); void toLogical(xyz_pos_t &raw); void toLogical(xyze_pos_t &raw); -void toNative(xy_pos_t &raw); -void toNative(xyz_pos_t &raw); -void toNative(xyze_pos_t &raw); +void toNative(xy_pos_t &lpos); +void toNative(xyz_pos_t &lpos); +void toNative(xyze_pos_t &lpos); // // Paired XY coordinates, counters, flags, etc. +// Always has XY elements regardless of the number of configured axes. // template struct XYval { union { struct { T x, y; }; + struct { T X, Y; }; struct { T a, b; }; + struct { T A, B; }; T pos[2]; }; // Set all to 0 - FI void reset() { x = y = 0; } + FI void reset() { x = y = 0; } // Setters taking struct types and arrays - FI void set(const T px) { x = px; } - #if HAS_Y_AXIS - FI void set(const T px, const T py) { x = px; y = py; } - FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } + #if HAS_X_AXIS + FI void set(const T px) { x = px; } #endif - #if NUM_AXES > XY - FI void set(const T (&arr)[NUM_AXES]) { x = arr[0]; y = arr[1]; } + #if HAS_Y_AXIS + FI void set(const T px, const T py) { x = px; y = py; } + FI void set(const T (&arr)[2]) { x = arr[0]; y = arr[1]; } + #endif + #if NUM_AXES > 2 + FI void set(const T (&arr)[NUM_AXES]) { x = arr[0]; y = arr[1]; } #endif #if LOGICAL_AXES > NUM_AXES - FI void set(const T (&arr)[LOGICAL_AXES]) { x = arr[0]; y = arr[1]; } + FI void set(const T (&arr)[LOGICAL_AXES]) { x = arr[0]; y = arr[1]; } #if DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } + FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } #endif #endif // Length reduced to one dimension - FI T magnitude() const { return (T)sqrtf(x*x + y*y); } + FI constexpr T magnitude() const { return (T)SQRT(x*x + y*y); } // Pointer to the data as a simple array - FI operator T* () { return pos; } + explicit FI operator T* () { return pos; } // If any element is true then it's true - FI operator bool() { return x || y; } + FI constexpr operator bool() const { return x || y; } + // Smallest element + FI constexpr T small() const { return _MIN(x, y); } + // Largest element + FI constexpr T large() const { return _MAX(x, y); } // Explicit copy and copies with conversion - FI XYval copy() const { return *this; } - FI XYval ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; } - FI XYval asInt() { return { int16_t(x), int16_t(y) }; } - FI XYval asInt() const { return { int16_t(x), int16_t(y) }; } - FI XYval asLong() { return { int32_t(x), int32_t(y) }; } - FI XYval asLong() const { return { int32_t(x), int32_t(y) }; } - FI XYval ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } - FI XYval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } - FI XYval asFloat() { return { static_cast(x), static_cast(y) }; } - FI XYval asFloat() const { return { static_cast(x), static_cast(y) }; } - FI XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } + FI constexpr XYval copy() const { return *this; } + FI constexpr XYval ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; } + FI constexpr XYval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } + FI constexpr XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } + + // Conversion to other types + FI constexpr XYval asInt16() const { return { int16_t(x), int16_t(y) }; } + FI constexpr XYval asInt32() const { return { int32_t(x), int32_t(y) }; } + FI constexpr XYval asUInt32() const { return { uint32_t(x), uint32_t(y) }; } + FI constexpr XYval asInt64() const { return { int64_t(x), int64_t(y) }; } + FI constexpr XYval asUInt64() const { return { uint64_t(x), uint64_t(y) }; } + FI constexpr XYval asFloat() const { return { float(x), float(y) }; } // Marlin workspace shifting is done with G92 and M206 - FI XYval asLogical() const { XYval o = asFloat(); toLogical(o); return o; } - FI XYval asNative() const { XYval o = asFloat(); toNative(o); return o; } + FI XYval asLogical() const { XYval o = asFloat(); toLogical(o); return o; } + FI XYval asNative() const { XYval o = asFloat(); toNative(o); return o; } // Cast to a type with more fields by making a new object - FI operator XYZval() { return { x, y }; } - FI operator XYZval() const { return { x, y }; } - FI operator XYZEval() { return { x, y }; } - FI operator XYZEval() const { return { x, y }; } + FI constexpr operator XYZval() const { return { x, y }; } + FI constexpr operator XYZEval() const { return { x, y }; } // Accessor via an AxisEnum (or any integer) [index] - FI T& operator[](const int n) { return pos[n]; } - FI const T& operator[](const int n) const { return pos[n]; } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } // Assignment operator overrides do the expected thing - FI XYval& operator= (const T v) { set(v, v ); return *this; } - FI XYval& operator= (const XYZval &rs) { set(rs.x, rs.y); return *this; } - FI XYval& operator= (const XYZEval &rs) { set(rs.x, rs.y); return *this; } + FI XYval& operator= (const T v) { set(v, v); return *this; } + FI XYval& operator= (const XYZval &rs) { set(XY_LIST(rs.x, rs.y)); return *this; } + FI XYval& operator= (const XYZEval &rs) { set(XY_LIST(rs.x, rs.y)); return *this; } // Override other operators to get intuitive behaviors - FI XYval operator+ (const XYval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator+ (const XYval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator- (const XYval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator- (const XYval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator* (const XYval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator* (const XYval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator/ (const XYval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator/ (const XYval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator+ (const XYZval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator+ (const XYZval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator- (const XYZval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator- (const XYZval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator* (const XYZval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator* (const XYZval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator/ (const XYZval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator/ (const XYZval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator+ (const XYZEval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator+ (const XYZEval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator- (const XYZEval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator- (const XYZEval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator* (const XYZEval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator* (const XYZEval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator/ (const XYZEval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator/ (const XYZEval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator* (const float &v) const { XYval ls = *this; ls.x *= v; ls.y *= v; return ls; } - FI XYval operator* (const float &v) { XYval ls = *this; ls.x *= v; ls.y *= v; return ls; } - FI XYval operator* (const int &v) const { XYval ls = *this; ls.x *= v; ls.y *= v; return ls; } - FI XYval operator* (const int &v) { XYval ls = *this; ls.x *= v; ls.y *= v; return ls; } - FI XYval operator/ (const float &v) const { XYval ls = *this; ls.x /= v; ls.y /= v; return ls; } - FI XYval operator/ (const float &v) { XYval ls = *this; ls.x /= v; ls.y /= v; return ls; } - FI XYval operator/ (const int &v) const { XYval ls = *this; ls.x /= v; ls.y /= v; return ls; } - FI XYval operator/ (const int &v) { XYval ls = *this; ls.x /= v; ls.y /= v; return ls; } - FI XYval operator>>(const int &v) const { XYval ls = *this; _RS(ls.x); _RS(ls.y); return ls; } - FI XYval operator>>(const int &v) { XYval ls = *this; _RS(ls.x); _RS(ls.y); return ls; } - FI XYval operator<<(const int &v) const { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } - FI XYval operator<<(const int &v) { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } - FI const XYval operator-() const { XYval o = *this; o.x = -x; o.y = -y; return o; } - FI XYval operator-() { XYval o = *this; o.x = -x; o.y = -y; return o; } + #define XY_OP(OP) { T(x TERN_(HAS_X_AXIS, OP rs.x)), T(y TERN_(HAS_Y_AXIS, OP rs.y)) } + FI constexpr XYval operator+ (const XYval &rs) const { return { T(x + rs.x), T(y + rs.y) }; } + FI constexpr XYval operator- (const XYval &rs) const { return { T(x - rs.x), T(y - rs.y) }; } + FI constexpr XYval operator* (const XYval &rs) const { return { T(x * rs.x), T(y * rs.y) }; } + FI constexpr XYval operator/ (const XYval &rs) const { return { T(x / rs.x), T(y / rs.y) }; } + FI constexpr XYval operator+ (const XYZval &rs) const { return { XY_OP(+) }; } + FI constexpr XYval operator- (const XYZval &rs) const { return { XY_OP(-) }; } + FI constexpr XYval operator* (const XYZval &rs) const { return { XY_OP(*) }; } + FI constexpr XYval operator/ (const XYZval &rs) const { return { XY_OP(/) }; } + FI constexpr XYval operator+ (const XYZEval &rs) const { return { XY_OP(+) }; } + FI constexpr XYval operator- (const XYZEval &rs) const { return { XY_OP(-) }; } + FI constexpr XYval operator* (const XYZEval &rs) const { return { XY_OP(*) }; } + FI constexpr XYval operator/ (const XYZEval &rs) const { return { XY_OP(/) }; } + FI constexpr XYval operator* (const float &p) const { return { (T)(x * p), (T)(y * p) }; } + FI constexpr XYval operator* (const int &p) const { return { x * p, y * p }; } + FI constexpr XYval operator/ (const float &p) const { return { (T)(x / p), (T)(y / p) }; } + FI constexpr XYval operator/ (const int &p) const { return { x / p, y / p }; } + FI constexpr XYval operator>>(const int &p) const { return { _RS(x), _RS(y) }; } + FI constexpr XYval operator<<(const int &p) const { return { _LS(x), _LS(y) }; } + FI constexpr XYval operator-() const { return { -x, -y }; } + #undef XY_OP // Modifier operators - FI XYval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYval& operator+=(const XYZval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYval& operator-=(const XYZval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYval& operator*=(const XYZval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYval& operator+=(const XYZEval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYval& operator-=(const XYZEval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYval& operator*=(const XYZEval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYval& operator*=(const float &v) { x *= v; y *= v; return *this; } - FI XYval& operator*=(const int &v) { x *= v; y *= v; return *this; } - FI XYval& operator>>=(const int &v) { _RS(x); _RS(y); return *this; } - FI XYval& operator<<=(const int &v) { _LS(x); _LS(y); return *this; } + FI XYval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } + FI XYval& operator+=(const XYZval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } + FI XYval& operator-=(const XYZval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } + FI XYval& operator*=(const XYZval &rs) { XY_CODE(x *= rs.x, y *= rs.y); return *this; } + FI XYval& operator/=(const XYZval &rs) { XY_CODE(x /= rs.x, y /= rs.y); return *this; } + FI XYval& operator+=(const XYZEval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } + FI XYval& operator-=(const XYZEval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } + FI XYval& operator*=(const XYZEval &rs) { XY_CODE(x *= rs.x, y *= rs.y); return *this; } + FI XYval& operator/=(const XYZEval &rs) { XY_CODE(x /= rs.x, y /= rs.y); return *this; } + FI XYval& operator*=(const float &p) { x *= p; y *= p; return *this; } + FI XYval& operator*=(const int &p) { x *= p; y *= p; return *this; } + FI XYval& operator>>=(const int &p) { _RSE(x); _RSE(y); return *this; } + FI XYval& operator<<=(const int &p) { _LSE(x); _LSE(y); return *this; } + + // Absolute difference between two objects + FI constexpr XYval diff(const XYZEval &rs) const { return { TERN(HAS_X_AXIS, T(_ABS(x - rs.x)), x), TERN(HAS_Y_AXIS, T(_ABS(y - rs.y)), y) }; } + FI constexpr XYval diff(const XYZval &rs) const { return { TERN(HAS_X_AXIS, T(_ABS(x - rs.x)), x), TERN(HAS_Y_AXIS, T(_ABS(y - rs.y)), y) }; } + FI constexpr XYval diff(const XYval &rs) const { return { T(_ABS(x - rs.x)), T(_ABS(y - rs.y)) }; } // Exact comparisons. For floats a "NEAR" operation may be better. - FI bool operator==(const XYval &rs) { return x == rs.x && y == rs.y; } - FI bool operator==(const XYZval &rs) { return x == rs.x && y == rs.y; } - FI bool operator==(const XYZEval &rs) { return x == rs.x && y == rs.y; } - FI bool operator==(const XYval &rs) const { return x == rs.x && y == rs.y; } - FI bool operator==(const XYZval &rs) const { return x == rs.x && y == rs.y; } - FI bool operator==(const XYZEval &rs) const { return x == rs.x && y == rs.y; } - FI bool operator!=(const XYval &rs) { return !operator==(rs); } - FI bool operator!=(const XYZval &rs) { return !operator==(rs); } - FI bool operator!=(const XYZEval &rs) { return !operator==(rs); } - FI bool operator!=(const XYval &rs) const { return !operator==(rs); } - FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } - FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + FI bool operator==(const XYval &rs) const { return x == rs.x && y == rs.y; } + FI bool operator==(const XYZval &rs) const { return ENABLED(HAS_X_AXIS) XY_GANG(&& x == rs.x, && y == rs.y); } + FI bool operator==(const XYZEval &rs) const { return ENABLED(HAS_X_AXIS) XY_GANG(&& x == rs.x, && y == rs.y); } + FI bool operator!=(const XYval &rs) const { return !operator==(rs); } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } + FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + + // Exact comparison to a single value + FI bool operator==(const T &p) const { return x == p && y == p; } + FI bool operator!=(const T &p) const { return !operator==(p); } + + FI bool operator< (const XYval &rs) const { return x < rs.x && y < rs.y; } + FI bool operator<=(const XYval &rs) const { return x <= rs.x && y <= rs.y; } + FI bool operator> (const XYval &rs) const { return x > rs.x && y > rs.y; } + FI bool operator>=(const XYval &rs) const { return x >= rs.x && y >= rs.y; } + + FI bool operator< (const XYZval &rs) const { return true XY_GANG(&& x < rs.x, && y < rs.y); } + FI bool operator<=(const XYZval &rs) const { return true XY_GANG(&& x <= rs.x, && y <= rs.y); } + FI bool operator> (const XYZval &rs) const { return true XY_GANG(&& x > rs.x, && y > rs.y); } + FI bool operator>=(const XYZval &rs) const { return true XY_GANG(&& x >= rs.x, && y >= rs.y); } + + FI bool operator< (const XYZEval &rs) const { return true XY_GANG(&& x < rs.x, && y < rs.y); } + FI bool operator<=(const XYZEval &rs) const { return true XY_GANG(&& x <= rs.x, && y <= rs.y); } + FI bool operator> (const XYZEval &rs) const { return true XY_GANG(&& x > rs.x, && y > rs.y); } + FI bool operator>=(const XYZEval &rs) const { return true XY_GANG(&& x >= rs.x, && y >= rs.y); } + }; // // Linear Axes coordinates, counters, flags, etc. +// May have any number of axes according to configuration, including zero axes. // template struct XYZval { union { - struct { T NUM_AXIS_ARGS(); }; - struct { T NUM_AXIS_LIST(a, b, c, _i, _j, _k, _u, _v, _w); }; + #if NUM_AXES + struct { NUM_AXIS_CODE(T x, T y, T z, T i, T j, T k, T u, T v, T w); }; + struct { NUM_AXIS_CODE(T X, T Y, T Z, T I, T J, T K, T U, T V, T W); }; + struct { NUM_AXIS_CODE(T a, T b, T c, T _i, T _j, T _k, T _u, T _v, T _w); }; + struct { NUM_AXIS_CODE(T A, T B, T C, T II, T JJ, T KK, T UU, T VV, T WW); }; + #endif T pos[NUM_AXES]; }; // Set all to 0 - FI void reset() { NUM_AXIS_GANG(x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; } + FI void reset() { NUM_AXIS_CODE(x = 0, y = 0, z = 0, i = 0, j = 0, k = 0, u = 0, v = 0, w = 0); } // Setters taking struct types and arrays - FI void set(const T px) { x = px; } - FI void set(const T px, const T py) { x = px; y = py; } - FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } - FI void set(const XYval pxy, const T pz) { NUM_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP); } - FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } - #if HAS_Z_AXIS - FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } - FI void set(NUM_AXIS_ARGS(const T)) { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w ); } - #endif + FI void set(const XYval &pxy) { XY_CODE(x = pxy.x, y = pxy.y); } + FI void set(const XYval &pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); } + FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #if LOGICAL_AXES > NUM_AXES - FI void set(const T (&arr)[LOGICAL_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } - FI void set(LOGICAL_AXIS_ARGS(const T)) { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w ); } + FI void set(const T (&arr)[LOGICAL_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(LOGICAL_AXIS_ARGS_LC(const T)) { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } #if DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(const T (&arr)[DISTINCT_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #endif #endif + + // Setter for all individual args + FI void set(NUM_AXIS_ARGS_LC(const T)) { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } + + // Setters with fewer elements leave the rest untouched + #if HAS_Y_AXIS + FI void set(const T px) { x = px; } + #endif + #if HAS_Z_AXIS + FI void set(const T px, const T py) { x = px; y = py; } + #endif #if HAS_I_AXIS FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } #endif @@ -494,133 +727,164 @@ struct XYZval { FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; } #endif #if HAS_V_AXIS - FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; } + FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; } #endif #if HAS_W_AXIS - FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm, const T po) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; v = pv; } + FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu, const T pv) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; v = pv; } #endif // Length reduced to one dimension - FI T magnitude() const { return (T)sqrtf(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); } + FI constexpr T magnitude() const { return (T)TERN(HAS_X_AXIS, SQRT(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)), 0); } // Pointer to the data as a simple array - FI operator T* () { return pos; } + explicit FI operator T* () { return pos; } // If any element is true then it's true - FI operator bool() { return NUM_AXIS_GANG(x, || y, || z, || i, || j, || k, || u, || v, || w); } + FI constexpr operator bool() const { return 0 NUM_AXIS_GANG(|| x, || y, || z, || i, || j, || k, || u, || v, || w); } + // Smallest element + FI constexpr T small() const { return TERN0(HAS_X_AXIS, _MIN(NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w))); } + // Largest element + FI constexpr T large() const { return TERN0(HAS_X_AXIS, _MAX(NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w))); } // Explicit copy and copies with conversion - FI XYZval copy() const { XYZval o = *this; return o; } - FI XYZval ABS() const { return NUM_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } - FI XYZval asInt() { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI XYZval asInt() const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI XYZval asLong() { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI XYZval asLong() const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI XYZval ROUNDL() { return NUM_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI XYZval ROUNDL() const { return NUM_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI XYZval asFloat() { return NUM_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI XYZval asFloat() const { return NUM_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI XYZval reciprocal() const { return NUM_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + FI constexpr XYZval copy() const { XYZval o = *this; return o; } + FI constexpr XYZval ABS() const { return NUM_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } + FI constexpr XYZval ROUNDL() const { return NUM_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } + FI constexpr XYZval reciprocal() const { return NUM_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + + // Conversion to other types + FI constexpr XYZval asInt16() const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } + FI constexpr XYZval asInt32() const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } + FI constexpr XYZval asUInt32() const { return NUM_AXIS_ARRAY(uint32_t(x), uint32_t(y), uint32_t(z), uint32_t(i), uint32_t(j), uint32_t(k), uint32_t(u), uint32_t(v), uint32_t(w)); } + FI constexpr XYZval asInt64() const { return NUM_AXIS_ARRAY(int64_t(x), int64_t(y), int64_t(z), int64_t(i), int64_t(j), int64_t(k), int64_t(u), int64_t(v), int64_t(w)); } + FI constexpr XYZval asUInt64() const { return NUM_AXIS_ARRAY(uint64_t(x), uint64_t(y), uint64_t(z), uint64_t(i), uint64_t(j), uint64_t(k), uint64_t(u), uint64_t(v), uint64_t(w)); } + FI constexpr XYZval asFloat() const { return NUM_AXIS_ARRAY(float(x), float(y), float(z), float(i), float(j), float(k), float(u), float(v), float(w)); } // Marlin workspace shifting is done with G92 and M206 - FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } - FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } + FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } + FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } - // In-place cast to types having fewer fields - FI operator XYval&() { return *(XYval*)this; } - FI operator const XYval&() const { return *(const XYval*)this; } + // In-place reinterpret-cast to types having fewer fields + FI operator XYval&() { return *(XYval*)this; } + FI operator const XYval&() const { return *(const XYval*)this; } // Cast to a type with more fields by making a new object - FI operator XYZEval() const { return NUM_AXIS_ARRAY(x, y, z, i, j, k, u, v, w); } + FI constexpr operator XYZEval() const { return NUM_AXIS_ARRAY(x, y, z, i, j, k, u, v, w); } // Accessor via an AxisEnum (or any integer) [index] - FI T& operator[](const int n) { return pos[n]; } - FI const T& operator[](const int n) const { return pos[n]; } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } // Assignment operator overrides do the expected thing - FI XYZval& operator= (const T v) { set(ARRAY_N_1(NUM_AXES, v)); return *this; } - FI XYZval& operator= (const XYval &rs) { set(rs.x, rs.y ); return *this; } - FI XYZval& operator= (const XYZEval &rs) { set(NUM_AXIS_ELEM(rs)); return *this; } + FI XYZval& operator= (const T v) { set(ARRAY_N_1(NUM_AXES, v)); return *this; } + FI XYZval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } + FI XYZval& operator= (const XYZEval &rs) { set(NUM_AXIS_ELEM_LC(rs)); return *this; } // Override other operators to get intuitive behaviors - FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP , NOOP , NOOP , NOOP ); return ls; } - FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP , NOOP , NOOP , NOOP ); return ls; } - FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP , NOOP , NOOP , NOOP ); return ls; } - FI XYZval operator- (const XYval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP , NOOP , NOOP , NOOP ); return ls; } - FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP , NOOP , NOOP , NOOP ); return ls; } - FI XYZval operator* (const XYval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP , NOOP , NOOP , NOOP ); return ls; } - FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP , NOOP , NOOP , NOOP ); return ls; } - FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP , NOOP , NOOP , NOOP ); return ls; } - FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZval operator* (const float &v) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; } - FI XYZval operator* (const float &v) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; } - FI XYZval operator* (const int &v) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; } - FI XYZval operator* (const int &v) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; } - FI XYZval operator/ (const float &v) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; } - FI XYZval operator/ (const float &v) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; } - FI XYZval operator/ (const int &v) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; } - FI XYZval operator/ (const int &v) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; } - FI XYZval operator>>(const int &v) const { XYZval ls = *this; NUM_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; } - FI XYZval operator>>(const int &v) { XYZval ls = *this; NUM_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; } - FI XYZval operator<<(const int &v) const { XYZval ls = *this; NUM_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; } - FI XYZval operator<<(const int &v) { XYZval ls = *this; NUM_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; } - FI const XYZval operator-() const { XYZval o = *this; NUM_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k, o.u = -u, o.v = -v, o.w = -w); return o; } - FI XYZval operator-() { XYZval o = *this; NUM_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k, o.u = -u, o.v = -v, o.w = -w); return o; } + FI constexpr XYZval operator+ (const XYval &rs) const { return NUM_AXIS_ARRAY(T(x + rs.x), T(y + rs.y), z, i, j, k, u, v, w ); } + FI constexpr XYZval operator- (const XYval &rs) const { return NUM_AXIS_ARRAY(T(x - rs.x), T(y - rs.y), z, i, j, k, u, v, w ); } + FI constexpr XYZval operator* (const XYval &rs) const { return NUM_AXIS_ARRAY(T(x * rs.x), T(y * rs.y), z, i, j, k, u, v, w ); } + FI constexpr XYZval operator/ (const XYval &rs) const { return NUM_AXIS_ARRAY(T(x / rs.x), T(y / rs.y), z, i, j, k, u, v, w ); } + FI constexpr XYZval operator+ (const XYZval &rs) const { return NUM_AXIS_ARRAY(T(x + rs.x), T(y + rs.y), T(z + rs.z), T(i + rs.i), T(j + rs.j), T(k + rs.k), T(u + rs.u), T(v + rs.v), T(w + rs.w) ); } + FI constexpr XYZval operator- (const XYZval &rs) const { return NUM_AXIS_ARRAY(T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w) ); } + FI constexpr XYZval operator* (const XYZval &rs) const { return NUM_AXIS_ARRAY(T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w) ); } + FI constexpr XYZval operator/ (const XYZval &rs) const { return NUM_AXIS_ARRAY(T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w) ); } + FI constexpr XYZval operator+ (const XYZEval &rs) const { return NUM_AXIS_ARRAY(T(x + rs.x), T(y + rs.y), T(z + rs.z), T(i + rs.i), T(j + rs.j), T(k + rs.k), T(u + rs.u), T(v + rs.v), T(w + rs.w) ); } + FI constexpr XYZval operator- (const XYZEval &rs) const { return NUM_AXIS_ARRAY(T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w) ); } + FI constexpr XYZval operator* (const XYZEval &rs) const { return NUM_AXIS_ARRAY(T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w) ); } + FI constexpr XYZval operator/ (const XYZEval &rs) const { return NUM_AXIS_ARRAY(T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w) ); } + FI constexpr XYZval operator* (const float &p) const { return NUM_AXIS_ARRAY(T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); } + FI constexpr XYZval operator* (const int &p) const { return NUM_AXIS_ARRAY(x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } + FI constexpr XYZval operator/ (const float &p) const { return NUM_AXIS_ARRAY(T(x / p), T(y / p), T(z / p), T(i / p), T(j / p), T(k / p), T(u / p), T(v / p), T(w / p)); } + FI constexpr XYZval operator/ (const int &p) const { return NUM_AXIS_ARRAY(x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } + FI constexpr XYZval operator>>(const int &p) const { return NUM_AXIS_ARRAY(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); } + FI constexpr XYZval operator<<(const int &p) const { return NUM_AXIS_ARRAY(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); } + FI constexpr XYZval operator-() const { return NUM_AXIS_ARRAY(-x, -y, -z, -i, -j, -k, -u, -v, -w); } + + // Absolute difference between two objects + FI constexpr XYZval diff(const XYZEval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZval diff(const XYZval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZval diff(const XYval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), z, i, j, k, u, v, w ); } // Modifier operators - FI XYZval& operator+=(const XYval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP ); return *this; } - FI XYZval& operator-=(const XYval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP ); return *this; } - FI XYZval& operator*=(const XYval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP ); return *this; } - FI XYZval& operator/=(const XYval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP ); return *this; } - FI XYZval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } - FI XYZval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } - FI XYZval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } - FI XYZval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } - FI XYZval& operator+=(const XYZEval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } - FI XYZval& operator-=(const XYZEval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } - FI XYZval& operator*=(const XYZEval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } - FI XYZval& operator/=(const XYZEval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } - FI XYZval& operator*=(const float &v) { NUM_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v, u *= v, v *= v, w *= v); return *this; } - FI XYZval& operator*=(const int &v) { NUM_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v, u *= v, v *= v, w *= v); return *this; } - FI XYZval& operator>>=(const int &v) { NUM_AXIS_CODE(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); return *this; } - FI XYZval& operator<<=(const int &v) { NUM_AXIS_CODE(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); return *this; } + FI XYZval& operator+=(const XYval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } + FI XYZval& operator-=(const XYval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } + FI XYZval& operator*=(const XYval &rs) { XY_CODE(x *= rs.x, y *= rs.y); return *this; } + FI XYZval& operator/=(const XYval &rs) { XY_CODE(x /= rs.x, y /= rs.y); return *this; } + FI XYZval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } + FI XYZval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } + FI XYZval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } + FI XYZval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } + FI XYZval& operator+=(const XYZEval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } + FI XYZval& operator-=(const XYZEval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } + FI XYZval& operator*=(const XYZEval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } + FI XYZval& operator/=(const XYZEval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } + FI XYZval& operator*=(const float &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } + FI XYZval& operator*=(const int &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } + FI XYZval& operator/=(const float &p) { NUM_AXIS_CODE(x /= p, y /= p, z /= p, i /= p, j /= p, k /= p, u /= p, v /= p, w /= p); return *this; } + FI XYZval& operator>>=(const int &p) { NUM_AXIS_CODE(_RSE(x), _RSE(y), _RSE(z), _RSE(i), _RSE(j), _RSE(k), _RSE(u), _RSE(v), _RSE(w)); return *this; } + FI XYZval& operator<<=(const int &p) { NUM_AXIS_CODE(_LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; } // Exact comparisons. For floats a "NEAR" operation may be better. - FI bool operator==(const XYZEval &rs) { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } - FI bool operator==(const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } - FI bool operator!=(const XYZEval &rs) { return !operator==(rs); } - FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + FI bool operator==(const XYZEval &rs) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + + // Exact comparison to a single value + FI bool operator==(const T &p) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == p, && y == p, && z == p, && i == p, && j == p, && k == p, && u == p, && v == p, && w == p); } + FI bool operator!=(const T &p) const { return !operator==(p); } + + FI bool operator< (const XYZval &rs) const { return true NUM_AXIS_GANG(&& x < rs.x, && y < rs.y, && z < rs.z, && i < rs.i, && j < rs.j, && k < rs.k, && u < rs.u, && v < rs.v, && w < rs.w); } + FI bool operator<=(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x <= rs.x, && y <= rs.y, && z <= rs.z, && i <= rs.i, && j <= rs.j, && k <= rs.k, && u <= rs.u, && v <= rs.v, && w <= rs.w); } + FI bool operator> (const XYZval &rs) const { return true NUM_AXIS_GANG(&& x > rs.x, && y > rs.y, && z > rs.z, && i > rs.i, && j > rs.j, && k > rs.k, && u > rs.u, && v > rs.v, && w > rs.w); } + FI bool operator>=(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x >= rs.x, && y >= rs.y, && z >= rs.z, && i >= rs.i, && j >= rs.j, && k >= rs.k, && u >= rs.u, && v >= rs.v, && w >= rs.w); } + + FI bool operator< (const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x < rs.x, && y < rs.y, && z < rs.z, && i < rs.i, && j < rs.j, && k < rs.k, && u < rs.u, && v < rs.v, && w < rs.w); } + FI bool operator<=(const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x <= rs.x, && y <= rs.y, && z <= rs.z, && i <= rs.i, && j <= rs.j, && k <= rs.k, && u <= rs.u, && v <= rs.v, && w <= rs.w); } + FI bool operator> (const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x > rs.x, && y > rs.y, && z > rs.z, && i > rs.i, && j > rs.j, && k > rs.k, && u > rs.u, && v > rs.v, && w > rs.w); } + FI bool operator>=(const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x >= rs.x, && y >= rs.y, && z >= rs.z, && i >= rs.i, && j >= rs.j, && k >= rs.k, && u >= rs.u, && v >= rs.v, && w >= rs.w); } + }; // // Logical Axes coordinates, counters, etc. +// May have any number of axes according to configuration, including zero axes. +// When there is no extruder, essentially identical to XYZval. // template struct XYZEval { union { + struct { T LOGICAL_AXIS_ARGS_LC(); }; struct { T LOGICAL_AXIS_ARGS(); }; struct { T LOGICAL_AXIS_LIST(_e, a, b, c, _i, _j, _k, _u, _v, _w); }; + struct { T LOGICAL_AXIS_LIST(EE, A, B, C, II, JJ, KK, UU, VV, WW); }; T pos[LOGICAL_AXES]; }; // Reset all to 0 - FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; } + FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; } - // Setters for some number of linear axes, not all - FI void set(const T px) { x = px; } - FI void set(const T px, const T py) { x = px; y = py; } + // Setters taking struct types and arrays + FI void set(const XYval &pxy) { XY_CODE(x = pxy.x, y = pxy.y); } + FI void set(const XYval &pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); } + FI void set(const XYZval &pxyz) { set(NUM_AXIS_ELEM_LC(pxyz)); } + FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + #if LOGICAL_AXES > NUM_AXES + FI void set(const T (&arr)[LOGICAL_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(const XYval &pxy, const T pz, const T pe) { set(pxy, pz); e = pe; } + FI void set(const XYZval &pxyz, const T pe) { set(pxyz); e = pe; } + FI void set(LOGICAL_AXIS_ARGS_LC(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } + #if DISTINCT_AXES > LOGICAL_AXES + FI void set(const T (&arr)[DISTINCT_AXES], const uint8_t eindex) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1 + eindex], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + #endif + #endif + + // Setter for all individual args + FI void set(NUM_AXIS_ARGS_LC(const T)) { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } + + // Setters with fewer elements leave the rest untouched + #if HAS_Y_AXIS + FI void set(const T px) { x = px; } + #endif + #if HAS_Z_AXIS + FI void set(const T px, const T py) { x = px; y = py; } + #endif #if HAS_I_AXIS FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } #endif @@ -634,130 +898,454 @@ struct XYZEval { FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; } #endif #if HAS_V_AXIS - FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; } + FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; } #endif #if HAS_W_AXIS - FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm, const T po) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pm; v = pv; } - #endif - - // Setters taking struct types and arrays - FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } - FI void set(const XYZval pxyz) { set(NUM_AXIS_ELEM(pxyz)); } - #if HAS_Z_AXIS - FI void set(NUM_AXIS_ARGS(const T)) { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } - #endif - FI void set(const XYval pxy, const T pz) { set(pxy); TERN_(HAS_Z_AXIS, z = pz); } - #if LOGICAL_AXES > NUM_AXES - FI void set(const XYval pxy, const T pz, const T pe) { set(pxy, pz); e = pe; } - FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } - FI void set(LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } + FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu, const T pv) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; v = pv; } #endif // Length reduced to one dimension - FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); } + FI constexpr T magnitude() const { return (T)SQRT(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); } // Pointer to the data as a simple array - FI operator T* () { return pos; } + explicit FI operator T* () { return pos; } // If any element is true then it's true - FI operator bool() { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k, || u, || v, || w); } + FI constexpr operator bool() const { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k, || u, || v, || w); } + // Smallest element + FI constexpr T small() const { return _MIN(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); } + // Largest element + FI constexpr T large() const { return _MAX(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); } // Explicit copy and copies with conversion - FI XYZEval copy() const { XYZEval v = *this; return v; } - FI XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } - FI XYZEval asInt() { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI XYZEval asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI XYZEval asLong() { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI XYZEval asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI XYZEval ROUNDL() { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI XYZEval asFloat() { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + FI constexpr XYZEval copy() const { XYZEval v = *this; return v; } + FI constexpr XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } + FI constexpr XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } + FI constexpr XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + + // Conversion to other types + FI constexpr XYZEval asInt16() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } + FI constexpr XYZEval asInt32() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } + FI constexpr XYZEval asUInt32() const { return LOGICAL_AXIS_ARRAY(uint32_t(e), uint32_t(x), uint32_t(y), uint32_t(z), uint32_t(i), uint32_t(j), uint32_t(k), uint32_t(u), uint32_t(v), uint32_t(w)); } + FI constexpr XYZEval asInt64() const { return LOGICAL_AXIS_ARRAY(int64_t(e), int64_t(x), int64_t(y), int64_t(z), int64_t(i), int64_t(j), int64_t(k), int64_t(u), int64_t(v), int64_t(w)); } + FI constexpr XYZEval asUInt64() const { return LOGICAL_AXIS_ARRAY(uint64_t(e), uint64_t(x), uint64_t(y), uint64_t(z), uint64_t(i), uint64_t(j), uint64_t(k), uint64_t(u), uint64_t(v), uint64_t(w)); } + FI constexpr XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(float(e), float(x), float(y), float(z), float(i), float(j), float(k), float(u), float(v), float(w)); } // Marlin workspace shifting is done with G92 and M206 - FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } - FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } + FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } + FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } - // In-place cast to types having fewer fields + // In-place reinterpret-cast to types having fewer fields FI operator XYval&() { return *(XYval*)this; } FI operator const XYval&() const { return *(const XYval*)this; } FI operator XYZval&() { return *(XYZval*)this; } FI operator const XYZval&() const { return *(const XYZval*)this; } // Accessor via an AxisEnum (or any integer) [index] - FI T& operator[](const int n) { return pos[n]; } - FI const T& operator[](const int n) const { return pos[n]; } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } // Assignment operator overrides do the expected thing - FI XYZEval& operator= (const T v) { set(LOGICAL_AXIS_LIST_1(v)); return *this; } - FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } - FI XYZEval& operator= (const XYZval &rs) { set(NUM_AXIS_ELEM(rs)); return *this; } + FI XYZEval& operator= (const T v) { set(LOGICAL_AXIS_LIST_1(v)); return *this; } + FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } + FI XYZEval& operator= (const XYZval &rs) { set(NUM_AXIS_ELEM_LC(rs)); return *this; } // Override other operators to get intuitive behaviors - FI XYZEval operator+ (const XYval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZEval operator+ (const XYval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZEval operator- (const XYval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZEval operator- (const XYval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZEval operator* (const XYval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZEval operator* (const XYval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZEval operator/ (const XYval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZEval operator/ (const XYval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZEval operator+ (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZEval operator+ (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZEval operator- (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZEval operator- (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZEval operator* (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZEval operator* (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZEval operator/ (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZEval operator/ (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZEval operator* (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; } - FI XYZEval operator* (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; } - FI XYZEval operator* (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; } - FI XYZEval operator* (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; } - FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; } - FI XYZEval operator/ (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; } - FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; } - FI XYZEval operator/ (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; } - FI XYZEval operator>>(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; } - FI XYZEval operator>>(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; } - FI XYZEval operator<<(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; } - FI XYZEval operator<<(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; } - FI const XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); } - FI XYZEval operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); } + FI constexpr XYZEval operator+ (const XYval &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x + rs.x), T(y + rs.y), z, i, j, k, u, v, w); } + FI constexpr XYZEval operator- (const XYval &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x - rs.x), T(y - rs.y), z, i, j, k, u, v, w); } + FI constexpr XYZEval operator* (const XYval &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x * rs.x), T(y * rs.y), z, i, j, k, u, v, w); } + FI constexpr XYZEval operator/ (const XYval &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x / rs.x), T(y / rs.y), z, i, j, k, u, v, w); } + FI constexpr XYZEval operator+ (const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x + rs.x), T(y + rs.y), T(z + rs.z), T(i + rs.i), T(j + rs.j), T(k + rs.k), T(u + rs.u), T(v + rs.v), T(w + rs.w)); } + FI constexpr XYZEval operator- (const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w)); } + FI constexpr XYZEval operator* (const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w)); } + FI constexpr XYZEval operator/ (const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w)); } + FI constexpr XYZEval operator+ (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(e + rs.e), T(x + rs.x), T(y + rs.y), T(z + rs.z), T(i + rs.i), T(j + rs.j), T(k + rs.k), T(u + rs.u), T(v + rs.v), T(w + rs.w)); } + FI constexpr XYZEval operator- (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(e - rs.e), T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w)); } + FI constexpr XYZEval operator* (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(e * rs.e), T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w)); } + FI constexpr XYZEval operator/ (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(e / rs.e), T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w)); } + FI constexpr XYZEval operator+ (const uint32_t &p) const { return LOGICAL_AXIS_ARRAY(T(e + p), T(x + p), T(y + p), T(z + p), T(i + p), T(j + p), T(k + p), T(u + p), T(v + p), T(w + p)); } + FI constexpr XYZEval operator* (const float &p) const { return LOGICAL_AXIS_ARRAY(T(e * p), T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); } + FI constexpr XYZEval operator* (const uint32_t &p) const { return LOGICAL_AXIS_ARRAY(T(e * p), T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); } + FI constexpr XYZEval operator& (const int64_t &p) const { return LOGICAL_AXIS_ARRAY(T(e & p), T(x & p), T(y & p), T(z & p), T(i & p), T(j & p), T(k & p), T(u & p), T(v & p), T(w & p)); } + FI constexpr XYZEval operator* (const int &p) const { return LOGICAL_AXIS_ARRAY(e * p, x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } + FI constexpr XYZEval operator/ (const float &p) const { return LOGICAL_AXIS_ARRAY(T(e / p), T(x / p), T(y / p), T(z / p), T(i / p), T(j / p), T(k / p), T(u / p), T(v / p), T(w / p)); } + FI constexpr XYZEval operator/ (const int &p) const { return LOGICAL_AXIS_ARRAY(e / p, x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } + FI constexpr XYZEval operator>>(const int &p) const { return LOGICAL_AXIS_ARRAY(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); } + FI constexpr XYZEval operator<<(const int &p) const { return LOGICAL_AXIS_ARRAY(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); } + FI constexpr XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); } + + // Absolute difference between two objects + FI constexpr XYZEval diff(const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(_ABS(e - rs.e)), T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZEval diff(const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(0, T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZEval diff(const XYval &rs) const { return LOGICAL_AXIS_ARRAY(0, T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), z, i, j, k, u, v, w ); } // Modifier operators - FI XYZEval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYZEval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYZEval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYZEval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } - FI XYZEval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } - FI XYZEval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } - FI XYZEval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } - FI XYZEval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } - FI XYZEval& operator+=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } - FI XYZEval& operator-=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } - FI XYZEval& operator*=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } - FI XYZEval& operator/=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } - FI XYZEval& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v, i *= v, j *= v, k *= v, u *= v, v *= v, w *= v); return *this; } - FI XYZEval& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); return *this; } - FI XYZEval& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); return *this; } + FI XYZEval& operator+=(const XYval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } + FI XYZEval& operator-=(const XYval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } + FI XYZEval& operator*=(const XYval &rs) { XY_CODE(x *= rs.x, y *= rs.y); return *this; } + FI XYZEval& operator/=(const XYval &rs) { XY_CODE(x /= rs.x, y /= rs.y); return *this; } + FI XYZEval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } + FI XYZEval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } + FI XYZEval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } + FI XYZEval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } + FI XYZEval& operator+=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } + FI XYZEval& operator-=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } + FI XYZEval& operator*=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } + FI XYZEval& operator/=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } + FI XYZEval& operator+=(const T &p) { LOGICAL_AXIS_CODE(e += p, x += p, y += p, z += p, i += p, j += p, k += p, u += p, v += p, w += p); return *this; } + FI XYZEval& operator-=(const T &p) { LOGICAL_AXIS_CODE(e -= p, x -= p, y -= p, z -= p, i -= p, j -= p, k -= p, u -= p, v -= p, w -= p); return *this; } + FI XYZEval& operator*=(const T &p) { LOGICAL_AXIS_CODE(e *= p, x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } + FI XYZEval& operator/=(const T &p) { LOGICAL_AXIS_CODE(e /= p, x /= p, y /= p, z /= p, i /= p, j /= p, k /= p, u /= p, v /= p, w /= p); return *this; } + FI XYZEval& operator>>=(const int &p) { LOGICAL_AXIS_CODE(_RSE(e), _RSE(x), _RSE(y), _RSE(z), _RSE(i), _RSE(j), _RSE(k), _RSE(u), _RSE(v), _RSE(w)); return *this; } + FI XYZEval& operator<<=(const int &p) { LOGICAL_AXIS_CODE(_LSE(e), _LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; } // Exact comparisons. For floats a "NEAR" operation may be better. - FI bool operator==(const XYZval &rs) { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } - FI bool operator==(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } - FI bool operator!=(const XYZval &rs) { return !operator==(rs); } - FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } + FI bool operator==(const XYZval &rs) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator==(const XYZEval &rs) const { return ANY(HAS_X_AXIS, HAS_EXTRUDERS) LOGICAL_AXIS_GANG(&& e == rs.e, && x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } + FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + + // Exact comparison to a single value + FI bool operator==(const T &p) const { return ENABLED(HAS_X_AXIS) LOGICAL_AXIS_GANG(&& e == p, && x == p, && y == p, && z == p, && i == p, && j == p, && k == p, && u == p, && v == p, && w == p); } + FI bool operator!=(const T &p) const { return !operator==(p); } + + FI bool operator< (const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e < rs.e, && x < rs.x, && y < rs.y, && z < rs.z, && i < rs.i, && j < rs.j, && k < rs.k, && u < rs.u, && v < rs.v, && w < rs.w); } + FI bool operator<=(const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e <= rs.e, && x <= rs.x, && y <= rs.y, && z <= rs.z, && i <= rs.i, && j <= rs.j, && k <= rs.k, && u <= rs.u, && v <= rs.v, && w <= rs.w); } + FI bool operator> (const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e > rs.e, && x > rs.x, && y > rs.y, && z > rs.z, && i > rs.i, && j > rs.j, && k > rs.k, && u > rs.u, && v > rs.v, && w > rs.w); } + FI bool operator>=(const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e >= rs.e, && x >= rs.x, && y >= rs.y, && z >= rs.z, && i >= rs.i, && j >= rs.j, && k >= rs.k, && u >= rs.u, && v >= rs.v, && w >= rs.w); } + + FI bool operator< (const XYZval &rs) const { return true NUM_AXIS_GANG(&& x < rs.x, && y < rs.y, && z < rs.z, && i < rs.i, && j < rs.j, && k < rs.k, && u < rs.u, && v < rs.v, && w < rs.w); } + FI bool operator<=(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x <= rs.x, && y <= rs.y, && z <= rs.z, && i <= rs.i, && j <= rs.j, && k <= rs.k, && u <= rs.u, && v <= rs.v, && w <= rs.w); } + FI bool operator> (const XYZval &rs) const { return true NUM_AXIS_GANG(&& x > rs.x, && y > rs.y, && z > rs.z, && i > rs.i, && j > rs.j, && k > rs.k, && u > rs.u, && v > rs.v, && w > rs.w); } + FI bool operator>=(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x >= rs.x, && y >= rs.y, && z >= rs.z, && i >= rs.i, && j >= rs.j, && k >= rs.k, && u >= rs.u, && v >= rs.v, && w >= rs.w); } + +}; + +#include // for memset + +// +// Axis indexed arrays of type T (x[SIZE], y[SIZE], etc.) +// +template +struct XYZarray { + typedef T el[SIZE]; + union { + el data[LOGICAL_AXES]; + struct { NUM_AXIS_CODE(T x, T y, T z, T i, T j, T k, T u, T v, T w); }; + struct { NUM_AXIS_CODE(T X, T Y, T Z, T I, T J, T K, T U, T V, T W); }; + struct { NUM_AXIS_CODE(T a, T b, T c, T _i, T _j, T _k, T _u, T _v, T _w); }; + struct { NUM_AXIS_CODE(T A, T B, T C, T II, T JJ, T KK, T UU, T VV, T WW); }; + }; + FI void reset() { ZERO(data); } + + FI void set(const int n, const XYval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); } + FI void set(const int n, const XYZval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + FI void set(const int n, const XYZEval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + + // Setter for all individual args + FI void set(const int n OPTARGS_NUM(const T)) { NUM_AXIS_CODE(a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); } + + // Setters with fewer elements leave the rest untouched + #if HAS_Y_AXIS + FI void set(const int n, const T px) { x[n] = px; } + #endif + #if HAS_Z_AXIS + FI void set(const int n, const T px, const T py) { x[n] = px; y[n] = py; } + #endif + #if HAS_I_AXIS + FI void set(const int n, const T px, const T py, const T pz) { x[n] = px; y[n] = py; z[n] = pz; } + #endif + #if HAS_J_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; } + #endif + #if HAS_K_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; } + #endif + #if HAS_U_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; } + #endif + #if HAS_V_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; u[n] = pu; } + #endif + #if HAS_W_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu, const T pv) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; u[n] = pu; v[n] = pv; } + #endif + + FI XYZval operator[](const int n) const { return XYZval(NUM_AXIS_ARRAY(x[n], y[n], z[n], i[n], j[n], k[n], u[n], v[n], w[n])); } +}; + +template +struct XYZEarray { + typedef T el[SIZE]; + union { + el data[LOGICAL_AXES]; + struct { el LOGICAL_AXIS_ARGS(); }; + struct { el LOGICAL_AXIS_ARGS_LC(); }; + struct { el LOGICAL_AXIS_LIST(EE, A, B, C, II, JJ, KK, UU, VV, WW); }; + struct { el LOGICAL_AXIS_LIST(_e, a, b, c, _i, _j, _k, _u, _v, _w); }; + }; + FI void reset() { ZERO(data); } + + FI void set(const int n, const XYval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); } + FI void set(const int n, const XYZval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + FI void set(const int n, const XYZEval &p) { LOGICAL_AXIS_CODE(e[n]=p.e, x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + + // Setter for all individual args + FI void set(const int n OPTARGS_NUM(const T)) { NUM_AXIS_CODE(a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); } + #if LOGICAL_AXES > NUM_AXES + FI void set(const int n, LOGICAL_AXIS_ARGS_LC(const T)) { LOGICAL_AXIS_CODE(_e[n] = e, a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); } + #endif + + // Setters with fewer elements leave the rest untouched + #if HAS_Y_AXIS + FI void set(const int n, const T px) { x[n] = px; } + #endif + #if HAS_Z_AXIS + FI void set(const int n, const T px, const T py) { x[n] = px; y[n] = py; } + #endif + #if HAS_I_AXIS + FI void set(const int n, const T px, const T py, const T pz) { x[n] = px; y[n] = py; z[n] = pz; } + #endif + #if HAS_J_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; } + #endif + #if HAS_K_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; } + #endif + #if HAS_U_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; } + #endif + #if HAS_V_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; u[n] = pu; } + #endif + #if HAS_W_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu, const T pv) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; u[n] = pu; v[n] = pv; } + #endif + + FI XYZEval operator[](const int n) const { return XYZval(LOGICAL_AXIS_ARRAY(e[n], x[n], y[n], z[n], i[n], j[n], k[n], u[n], v[n], w[n])); } +}; + +// +// Axes mapped to bits in a mask of minimum size, bits_t(NUM_AXIS_HEADS) +// +class AxisBits { +public: + typedef bits_t(NUM_AXIS_HEADS) el; + union { + el bits; + // Axes x, y, z ... e0, e1, e2 ... hx, hy, hz + struct { + #if NUM_AXES + bool NUM_AXIS_LIST(x:1, y:1, z:1, i:1, j:1, k:1, u:1, v:1, w:1); + #endif + #define _EN_ITEM(N) bool e##N:1; + REPEAT(EXTRUDERS,_EN_ITEM) + #undef _EN_ITEM + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) + bool hx:1, hy:1, hz:1; + #endif + }; + // Axes X, Y, Z ... E0, E1, E2 ... HX, HY, HZ + struct { + #if NUM_AXES + bool NUM_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, W:1); + #endif + #define _EN_ITEM(N) bool E##N:1; + REPEAT(EXTRUDERS,_EN_ITEM) + #undef _EN_ITEM + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) + bool HX:1, HY:1, HZ:1; + #endif + }; + // a, b, c, e ... ha, hb, hc + struct { + bool LOGICAL_AXIS_LIST(e:1, a:1, b:1, c:1, ii:1, jj:1, kk:1, uu:1, vv:1, ww:1); + #if EXTRUDERS > 1 + #define _EN_ITEM(N) bool _e##N:1; + REPEAT_S(1,EXTRUDERS,_EN_ITEM) + #undef _EN_ITEM + #endif + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) + bool ha:1, hb:1, hc:1; + #endif + }; + // A, B, C, E ... HA, HB, HC + struct { + bool LOGICAL_AXIS_LIST(E:1, A:1, B:1, C:1, II:1, JJ:1, KK:1, UU:1, VV:1, WW:1); + #if EXTRUDERS > 1 + #define _EN_ITEM(N) bool _E##N:1; + REPEAT_S(1,EXTRUDERS,_EN_ITEM) + #undef _EN_ITEM + #endif + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) + bool HA:1, HB:1, HC:1; + #endif + }; + }; + + class BitProxy { + public: + BitProxy(el& data, int bit) : data_(data), bit_(bit) {} + + BitProxy& operator=(const bool value) { + if (value) + data_ |= (el(1) << bit_); + else + data_ &= ~(el(1) << bit_); + return *this; + } + + operator bool() const { return bool(data_ & (el(1) << bit_)); } + + private: + el& data_; + uint8_t bit_; + }; + + AxisBits() { reset(); } + + // Constructor, setter, and operator= for bit mask + AxisBits(const el p) { set(p); } + FI void set(const el p) { bits = el(p); } + FI AxisBits& operator=(const el p) { set(p); return *this; } + + FI void reset() { set(0); } + FI void fill() { set(_BV(NUM_AXIS_HEADS) - 1); } + + #define MSET(pE,pX,pY,pZ,pI,pJ,pK,pU,pV,pW) LOGICAL_AXIS_CODE(e=pE, x=pX, y=pY, z=pZ, i=pI, j=pJ, k=pK, u=pU, v=pV, w=pW) + + // Constructor, setter, and operator= for XYZE type + AxisBits(const xyze_bool_t &p) { set(p); } + FI void set(const xyze_bool_t &p) { + MSET(p.e, p.x, p.y, p.z, p.i, p.j, p.k, p.u, p.v, p.w); + } + FI AxisBits& operator=(const xyze_bool_t &p) { set(p); return *this; } + + // Constructor, setter, and operator= for bool array + AxisBits(const bool (&p)[LOGICAL_AXES]) { set(p); } + FI void set(const bool (&p)[LOGICAL_AXES]) { + MSET(p[E_AXIS], p[X_AXIS], p[Y_AXIS], p[Z_AXIS], + p[I_AXIS], p[J_AXIS], p[K_AXIS], + p[U_AXIS], p[V_AXIS], p[W_AXIS]); + } + FI AxisBits& operator=(const bool (&p)[LOGICAL_AXES]) { set(p); return *this; } + + // Constructor, setter, and operator= for undersized bool arrays + #if LOGICAL_AXES > 1 + AxisBits(const bool (&p)[1]) { set(p); } + FI void set(const bool (&p)[1]) { + MSET(0, p[X_AXIS], 0, 0, 0, 0, 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[1]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 2 + AxisBits(const bool (&p)[2]) { set(p); } + FI void set(const bool (&p)[2]) { + MSET(0, p[X_AXIS], p[Y_AXIS], 0, 0, 0, 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[2]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 3 + AxisBits(const bool (&p)[3]) { set(p); } + FI void set(const bool (&p)[3]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], 0, 0, 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[3]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 4 + AxisBits(const bool (&p)[4]) { set(p); } + FI void set(const bool (&p)[4]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], 0, 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[4]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 5 + AxisBits(const bool (&p)[5]) { set(p); } + FI void set(const bool (&p)[5]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[5]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 6 + AxisBits(const bool (&p)[6]) { set(p); } + FI void set(const bool (&p)[6]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], p[K_AXIS], 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[6]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 7 + AxisBits(const bool (&p)[7]) { set(p); } + FI void set(const bool (&p)[7]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], p[K_AXIS], p[U_AXIS], 0, 0); + } + FI AxisBits& operator=(const bool (&p)[7]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 8 + AxisBits(const bool (&p)[8]) { set(p); } + FI void set(const bool (&p)[8]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], p[K_AXIS], p[U_AXIS], p[V_AXIS], 0); + } + FI AxisBits& operator=(const bool (&p)[8]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 9 + AxisBits(const bool (&p)[9]) { set(p); } + FI void set(const bool (&p)[9]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], p[K_AXIS], p[U_AXIS], p[V_AXIS], p[W_AXIS]); + } + FI AxisBits& operator=(const bool (&p)[9]) { set(p); return *this; } + #endif + #undef MSET + + FI bool toggle(const AxisEnum n) { TBI(bits, n); return TEST(bits, n); } + FI void bset(const AxisEnum n) { SBI(bits, n); } + FI void bclr(const AxisEnum n) { CBI(bits, n); } + FI void bset(const AxisEnum n, const bool b) { if (b) bset(n); else bclr(n); } + + // Accessor via an AxisEnum (or any integer) [index] + FI BitProxy operator[](const int n) { return BitProxy(bits, n); } + FI BitProxy operator[](const AxisEnum n) { return BitProxy(bits, n); } + FI bool operator[](const int n) const { return TEST(bits, n); } + FI bool operator[](const AxisEnum n) const { return TEST(bits, n); } + + FI AxisBits& operator|=(const el &p) { bits |= el(p); return *this; } + FI AxisBits& operator&=(const el &p) { bits &= el(p); return *this; } + FI AxisBits& operator^=(const el &p) { bits ^= el(p); return *this; } + + FI AxisBits& operator|=(const AxisBits &p) { bits |= p.bits; return *this; } + FI AxisBits& operator&=(const AxisBits &p) { bits &= p.bits; return *this; } + FI AxisBits& operator^=(const AxisBits &p) { bits ^= p.bits; return *this; } + + FI bool operator==(const AxisBits &p) const { return p.bits == bits; } + FI bool operator!=(const AxisBits &p) const { return p.bits != bits; } + + FI el operator|(const el &p) const { return bits | el(p); } + FI el operator&(const el &p) const { return bits & el(p); } + FI el operator^(const el &p) const { return bits ^ el(p); } + + FI AxisBits operator|(const AxisBits &p) const { return AxisBits(bits | p.bits); } + FI AxisBits operator&(const AxisBits &p) const { return AxisBits(bits & p.bits); } + FI AxisBits operator^(const AxisBits &p) const { return AxisBits(bits ^ p.bits); } + FI AxisBits operator~() const { return AxisBits(~bits); } + + FI operator bool() const { return !!bits; } + FI operator uint16_t() const { return uint16_t(bits & 0xFFFF); } + FI operator uint32_t() const { return uint32_t(bits); } + }; #undef _RECIP #undef _ABS #undef _LS #undef _RS +#undef _LSE +#undef _RSE #undef FI + +// Axis names for G-code parsing, reports, etc. +constexpr xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME, AXIS7_NAME, AXIS8_NAME, AXIS9_NAME); +#if NUM_AXES <= 3 && !HAS_EXTRUDERS + #define AXIS_CHAR(A) ((char)('X' + A)) + #define IAXIS_CHAR AXIS_CHAR +#else + constexpr xyze_char_t iaxis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', 'I', 'J', 'K', 'U', 'V', 'W'); + #define AXIS_CHAR(A) axis_codes[A] + #define IAXIS_CHAR(A) iaxis_codes[A] +#endif diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 64f083e197..f6b8b304c0 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -22,22 +22,16 @@ #include "utility.h" -#include "../MarlinCore.h" #include "../module/temperature.h" -void safe_delay(millis_t ms) { - while (ms > 50) { - ms -= 50; - delay(50); - thermalManager.task(); - } - delay(ms); - thermalManager.task(); // This keeps us safe if too many small safe_delay() calls are made -} +#if ENABLED(MARLIN_DEV_MODE) + MarlinError marlin_error_number; // Error Number - Marlin can beep X times periodically, display, and emit... +#endif // A delay to provide brittle hosts time to receive bytes #if ENABLED(SERIAL_OVERRUN_PROTECTION) + #include "../MarlinCore.h" // for safe_delay #include "../gcode/gcode.h" // for set_autoreport_paused void serial_delay(const millis_t ms) { @@ -56,27 +50,38 @@ void safe_delay(millis_t ms) { #include "../feature/bedlevel/bedlevel.h" void log_machine_info() { - SERIAL_ECHOLNPGM("Machine Type: " - TERN_(DELTA, "Delta") - TERN_(IS_SCARA, "SCARA") - TERN_(IS_CORE, "Core") - TERN_(MARKFORGED_XY, "MarkForgedXY") - TERN_(MARKFORGED_YX, "MarkForgedYX") - TERN_(IS_CARTESIAN, "Cartesian") + SERIAL_ECHOLNPGM("Machine Type:" + TERN_(DELTA, " Delta") + TERN_(IS_SCARA, " SCARA") + TERN_(AXEL_TPARA, " TPARA") + TERN_(IS_CORE, " Core") + TERN_(BELTPRINTER, " Belt Printer") + TERN_(MARKFORGED_XY, " MarkForgedXY") + TERN_(MARKFORGED_YX, " MarkForgedYX") + TERN_(POLAR, " Polar") + TERN_(POLARGRAPH, " Polargraph") + TERN_(ARTICULATED_ROBOT_ARM, " Robot Arm") + TERN_(FOAMCUTTER_XYUV, " Foam Cutter") + TERN_(IS_CARTESIAN, " Cartesian") ); SERIAL_ECHOLNPGM("Probe: " - TERN_(PROBE_MANUALLY, "PROBE_MANUALLY") - TERN_(NOZZLE_AS_PROBE, "NOZZLE_AS_PROBE") - TERN_(FIX_MOUNTED_PROBE, "FIX_MOUNTED_PROBE") - TERN_(HAS_Z_SERVO_PROBE, TERN(BLTOUCH, "BLTOUCH", "SERVO PROBE")) - TERN_(BD_SENSOR, "BD_SENSOR") - TERN_(TOUCH_MI_PROBE, "TOUCH_MI_PROBE") - TERN_(Z_PROBE_SLED, "Z_PROBE_SLED") - TERN_(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY") - TERN_(SOLENOID_PROBE, "SOLENOID_PROBE") - TERN_(MAGLEV4, "MAGLEV4") - IF_DISABLED(PROBE_SELECTED, "NONE") + TERN_(PROBE_MANUALLY, "PROBE_MANUALLY") + TERN_(NOZZLE_AS_PROBE, "NOZZLE_AS_PROBE") + TERN_(FIX_MOUNTED_PROBE, "FIX_MOUNTED_PROBE") + TERN_(HAS_Z_SERVO_PROBE, TERN(BLTOUCH, "BLTOUCH", "SERVO PROBE")) + TERN_(BD_SENSOR, "BD_SENSOR") + TERN_(TOUCH_MI_PROBE, "TOUCH_MI_PROBE") + TERN_(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY") + TERN_(Z_PROBE_SLED, "Z_PROBE_SLED") + TERN_(RACK_AND_PINION_PROBE, "RACK_AND_PINION_PROBE") + TERN_(SOLENOID_PROBE, "SOLENOID_PROBE") + TERN_(SENSORLESS_PROBING, "SENSORLESS_PROBING") + TERN_(MAGLEV4, "MAGLEV4") + TERN_(MAG_MOUNTED_PROBE, "MAG_MOUNTED_PROBE") + TERN_(BIQU_MICROPROBE_V1, "BIQU_MICROPROBE_V1") + TERN_(BIQU_MICROPROBE_V2, "BIQU_MICROPROBE_V2") + IF_DISABLED(PROBE_SELECTED, "NONE") ); #if HAS_BED_PROBE @@ -95,9 +100,9 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM(" (Aligned With"); if (probe.offset_xy.y > 0) - SERIAL_ECHOF(F(TERN(IS_SCARA, "-Distal", "-Back"))); + SERIAL_ECHO(F(TERN(IS_SCARA, "-Distal", "-Back"))); else if (probe.offset_xy.y < 0) - SERIAL_ECHOF(F(TERN(IS_SCARA, "-Proximal", "-Front"))); + SERIAL_ECHO(F(TERN(IS_SCARA, "-Proximal", "-Front"))); else if (probe.offset_xy.x != 0) SERIAL_ECHOPGM("-Center"); @@ -105,7 +110,7 @@ void safe_delay(millis_t ms) { #endif - SERIAL_ECHOF(probe.offset.z < 0 ? F("Below") : probe.offset.z > 0 ? F("Above") : F("Same Z as")); + SERIAL_ECHO(probe.offset.z < 0 ? F("Below") : probe.offset.z > 0 ? F("Above") : F("Same Z as")); SERIAL_ECHOLNPGM(" Nozzle)"); #endif @@ -128,7 +133,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM("ABL Adjustment"); LOOP_NUM_AXES(a) { SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_STR[a])); - serial_offset(planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]); + serial_offset(planner.get_axis_position_mm((AxisEnum)a) - current_position[a]); } #else #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -139,10 +144,8 @@ void safe_delay(millis_t ms) { const float rz = bedlevel.get_z_correction(current_position); SERIAL_ECHO(ftostr43sign(rz, '+')); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - if (planner.z_fade_height) { - SERIAL_ECHOPGM(" (", ftostr43sign(rz * planner.fade_scaling_factor_for_z(current_position.z), '+')); - SERIAL_CHAR(')'); - } + if (planner.z_fade_height) + SERIAL_ECHO(F(" ("), ftostr43sign(rz * planner.fade_scaling_factor_for_z(current_position.z), '+'), C(')')); #endif #endif } @@ -161,10 +164,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM("MBL Adjustment Z", ftostr43sign(z_offset + z_correction, '+')); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (planner.z_fade_height) { - SERIAL_ECHOPGM(" (", ftostr43sign( - z_offset + z_correction * planner.fade_scaling_factor_for_z(current_position.z), '+' - )); - SERIAL_CHAR(')'); + SERIAL_ECHO(F(" ("), ftostr43sign(z_offset + z_correction * planner.fade_scaling_factor_for_z(current_position.z), '+'), C(')')); } #endif } diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index 2731e62b67..b8b4de7f28 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -25,25 +25,23 @@ #include "../core/types.h" #include "../core/millis_t.h" -void safe_delay(millis_t ms); // Delay ensuring that temperatures are updated and the watchdog is kept alive. - #if ENABLED(SERIAL_OVERRUN_PROTECTION) void serial_delay(const millis_t ms); #else inline void serial_delay(const millis_t) {} #endif -#if (GRID_MAX_POINTS_X) && (GRID_MAX_POINTS_Y) +#if GRID_MAX_POINTS // 16x16 bit arrays template struct FlagBits { - typename IF<(W>8), uint16_t, uint8_t>::type bits[H]; - void fill() { memset(bits, 0xFF, sizeof(bits)); } - void reset() { memset(bits, 0x00, sizeof(bits)); } - void unmark(const uint8_t x, const uint8_t y) { CBI(bits[y], x); } - void mark(const uint8_t x, const uint8_t y) { SBI(bits[y], x); } - bool marked(const uint8_t x, const uint8_t y) { return TEST(bits[y], x); } + bits_t(W) flags[H]; + void fill() { memset(flags, 0xFF, sizeof(flags)); } + void reset() { memset(flags, 0x00, sizeof(flags)); } + void unmark(const uint8_t x, const uint8_t y) { CBI(flags[y], x); } + void mark(const uint8_t x, const uint8_t y) { SBI(flags[y], x); } + bool marked(const uint8_t x, const uint8_t y) { return TEST(flags[y], x); } inline void unmark(const xy_int8_t &xy) { unmark(xy.x, xy.y); } inline void mark(const xy_int8_t &xy) { mark(xy.x, xy.y); } inline bool marked(const xy_int8_t &xy) { return marked(xy.x, xy.y); } @@ -82,13 +80,21 @@ public: // in the range 0-100 while avoiding rounding artifacts constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; } -// Axis names for G-code parsing, reports, etc. -const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME, AXIS7_NAME, AXIS8_NAME, AXIS9_NAME); -#if NUM_AXES <= XYZ && !HAS_EXTRUDERS - #define AXIS_CHAR(A) ((char)('X' + A)) - #define IAXIS_CHAR AXIS_CHAR -#else - const xyze_char_t iaxis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', 'I', 'J', 'K', 'U', 'V', 'W'); - #define AXIS_CHAR(A) axis_codes[A] - #define IAXIS_CHAR(A) iaxis_codes[A] +#if ENABLED(MARLIN_DEV_MODE) + enum MarlinError : uint8_t { + ERR_NONE, + ERR_STRING_RANGE, // A string buffer was too small to set the whole blob + ERR_ASSERTION, // An assertion was triggered + ERR_MALFUNCTION, + ERR_MEMORY_LEAK, + ERR_COMMS_SERIAL, + ERR_COMMS_SPI, + ERR_PLANNER_STARVED, + ERR_TMC_SHUTDOWN, + ERR_PROCEDURE_FAILED, + ERR_TOO_WACK, + ERR_PLAID_IN_SUMMER + }; + extern MarlinError marlin_error_number; // Error Number - Marlin can beep, display, and emit... + inline void error(const MarlinError err) { marlin_error_number = err; } #endif diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index 2e3d6a9fd2..d61784517b 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -25,8 +25,7 @@ #if ENABLED(BABYSTEPPING) #include "babystep.h" -#include "../MarlinCore.h" -#include "../module/motion.h" // for axes_should_home() +#include "../module/motion.h" // for axis_should_home(), BABYSTEP_ALLOWED #include "../module/planner.h" // for axis_steps_per_mm[] #include "../module/stepper.h" @@ -42,38 +41,52 @@ volatile int16_t Babystep::steps[BS_AXIS_IND(Z_AXIS) + 1]; #endif int16_t Babystep::accum; +#if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) + int16_t Babystep::ep_babysteps; +#endif + void Babystep::step_axis(const AxisEnum axis) { const int16_t curTodo = steps[BS_AXIS_IND(axis)]; // get rid of volatile for performance if (curTodo) { - stepper.do_babystep((AxisEnum)axis, curTodo > 0); + stepper.do_babystep(axis, curTodo > 0); if (curTodo > 0) steps[BS_AXIS_IND(axis)]--; else steps[BS_AXIS_IND(axis)]++; } } -void Babystep::add_mm(const AxisEnum axis, const_float_t mm) { +void Babystep::add_mm(const AxisEnum axis, const float mm) { add_steps(axis, mm * planner.settings.axis_steps_per_mm[axis]); } #if ENABLED(BD_SENSOR) - void Babystep::set_mm(const AxisEnum axis, const_float_t mm) { - //if (DISABLED(BABYSTEP_WITHOUT_HOMING) && axes_should_home(_BV(axis))) return; + void Babystep::set_mm(const AxisEnum axis, const float mm) { + //if (DISABLED(BABYSTEP_WITHOUT_HOMING) && axis_should_home(axis)) return; const int16_t distance = mm * planner.settings.axis_steps_per_mm[axis]; accum = distance; // Count up babysteps for the UI steps[BS_AXIS_IND(axis)] = distance; TERN_(BABYSTEP_DISPLAY_TOTAL, axis_total[BS_TOTAL_IND(axis)] = distance); TERN_(BABYSTEP_ALWAYS_AVAILABLE, gcode.reset_stepper_timeout()); - TERN_(INTEGRATED_BABYSTEPPING, if (has_steps()) stepper.initiateBabystepping()); + TERN_(BABYSTEPPING, if (has_steps()) stepper.initiateBabystepping()); } #endif +bool Babystep::can_babystep(const AxisEnum axis) { + return (ENABLED(BABYSTEP_WITHOUT_HOMING) || !axis_should_home(axis)); +} + void Babystep::add_steps(const AxisEnum axis, const int16_t distance) { - if (DISABLED(BABYSTEP_WITHOUT_HOMING) && axes_should_home(_BV(axis))) return; + if (!can_babystep(axis)) return; accum += distance; // Count up babysteps for the UI steps[BS_AXIS_IND(axis)] += distance; TERN_(BABYSTEP_DISPLAY_TOTAL, axis_total[BS_TOTAL_IND(axis)] += distance); TERN_(BABYSTEP_ALWAYS_AVAILABLE, gcode.reset_stepper_timeout()); - TERN_(INTEGRATED_BABYSTEPPING, if (has_steps()) stepper.initiateBabystepping()); + TERN_(BABYSTEPPING, if (has_steps()) stepper.initiateBabystepping()); } +#if ENABLED(EP_BABYSTEPPING) + // Step Z for M293 / M294 + void Babystep::z_up() { if (BABYSTEP_ALLOWED()) add_steps(Z_AXIS, +BABYSTEP_SIZE_Z); } + void Babystep::z_down() { if (BABYSTEP_ALLOWED()) add_steps(Z_AXIS, -BABYSTEP_SIZE_Z); } +#endif + #endif // BABYSTEPPING diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h index bbf0c5a260..da330672b2 100644 --- a/Marlin/src/feature/babystep.h +++ b/Marlin/src/feature/babystep.h @@ -23,15 +23,10 @@ #include "../inc/MarlinConfigPre.h" -#if ENABLED(INTEGRATED_BABYSTEPPING) - #define BABYSTEPS_PER_SEC 1000UL - #define BABYSTEP_TICKS ((STEPPER_TIMER_RATE) / (BABYSTEPS_PER_SEC)) -#else - #define BABYSTEPS_PER_SEC 976UL - #define BABYSTEP_TICKS ((TEMP_TIMER_RATE) / (BABYSTEPS_PER_SEC)) -#endif +#define BABYSTEPS_PER_SEC 1000UL +#define BABYSTEP_TICKS ((STEPPER_TIMER_RATE) / (BABYSTEPS_PER_SEC)) -#if IS_CORE || EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS) +#if ANY(IS_CORE, BABYSTEP_XY, I2C_POSITION_ENCODERS) #define BS_AXIS_IND(A) A #define BS_AXIS(I) AxisEnum(I) #else @@ -52,6 +47,10 @@ public: static volatile int16_t steps[BS_AXIS_IND(Z_AXIS) + 1]; static int16_t accum; // Total babysteps in current edit + #if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) + static int16_t ep_babysteps; + #endif + #if ENABLED(BABYSTEP_DISPLAY_TOTAL) static int16_t axis_total[BS_TOTAL_IND(Z_AXIS) + 1]; // Total babysteps since G28 static void reset_total(const AxisEnum axis) { @@ -60,11 +59,27 @@ public: } #endif + static bool can_babystep(const AxisEnum axis); static void add_steps(const AxisEnum axis, const int16_t distance); - static void add_mm(const AxisEnum axis, const_float_t mm); + static void add_mm(const AxisEnum axis, const float mm); + + #if ENABLED(EP_BABYSTEPPING) + // Step Z for M293 / M294 + static void z_up(); + static void z_down(); + #if ENABLED(EMERGENCY_PARSER) + // Step Z according to steps accumulated by the EP + FORCE_INLINE static void do_ep_steps() { + if (ep_babysteps) { + if (ep_babysteps > 0) { z_up(); ep_babysteps--; } + else { z_down(); ep_babysteps++; } + } + } + #endif + #endif // EP_BABYSTEPPING #if ENABLED(BD_SENSOR) - static void set_mm(const AxisEnum axis, const_float_t mm); + static void set_mm(const AxisEnum axis, const float mm); #endif static bool has_steps() { @@ -76,7 +91,7 @@ public: // apply accumulated babysteps to the axes. // static void task() { - LOOP_LE_N(i, BS_AXIS_IND(Z_AXIS)) step_axis(BS_AXIS(i)); + for (uint8_t i = 0; i <= BS_AXIS_IND(Z_AXIS); ++i) step_axis(BS_AXIS(i)); } private: diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 13e2cd99ec..3b9d78cb2e 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -29,7 +29,7 @@ #include "../module/motion.h" #include "../module/planner.h" -axis_bits_t Backlash::last_direction_bits; +AxisBits Backlash::last_direction_bits; xyz_long_t Backlash::residual_error{0}; #ifdef BACKLASH_DISTANCE_MM @@ -63,25 +63,25 @@ Backlash backlash; * spread over multiple segments, smoothing out artifacts even more. */ -void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block) { - axis_bits_t changed_dir = last_direction_bits ^ dm; +void Backlash::add_correction_steps(const xyze_long_t &dist, const AxisBits dm, block_t * const block) { + AxisBits changed_dir = last_direction_bits ^ dm; // Ignore direction change unless steps are taken in that direction - #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) - if (!da) CBI(changed_dir, X_AXIS); - if (!db) CBI(changed_dir, Y_AXIS); - if (!dc) CBI(changed_dir, Z_AXIS); + #if DISABLED(CORE_BACKLASH) || ANY(MARKFORGED_XY, MARKFORGED_YX) + if (!dist.a) changed_dir.x = false; + if (!dist.b) changed_dir.y = false; + if (!dist.c) changed_dir.z = false; #elif CORE_IS_XY - if (!(da + db)) CBI(changed_dir, X_AXIS); - if (!(da - db)) CBI(changed_dir, Y_AXIS); - if (!dc) CBI(changed_dir, Z_AXIS); + if (!(dist.a + dist.b)) changed_dir.x = false; + if (!(dist.a - dist.b)) changed_dir.y = false; + if (!dist.c) changed_dir.z = false; #elif CORE_IS_XZ - if (!(da + dc)) CBI(changed_dir, X_AXIS); - if (!(da - dc)) CBI(changed_dir, Z_AXIS); - if (!db) CBI(changed_dir, Y_AXIS); + if (!(dist.a + dist.c)) changed_dir.x = false; + if (!(dist.a - dist.c)) changed_dir.z = false; + if (!dist.b) changed_dir.y = false; #elif CORE_IS_YZ - if (!(db + dc)) CBI(changed_dir, Y_AXIS); - if (!(db - dc)) CBI(changed_dir, Z_AXIS); - if (!da) CBI(changed_dir, X_AXIS); + if (!(dist.b + dist.c)) changed_dir.y = false; + if (!(dist.b - dist.c)) changed_dir.z = false; + if (!dist.a) changed_dir.x = false; #endif last_direction_bits ^= changed_dir; @@ -97,18 +97,24 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const const float f_corr = float(correction) / all_on; + bool changed = false; + float millimeters_delta = 0.0f; + #if IS_KINEMATIC + float sqr_stepper_space_mm = 0.0f; + #endif + LOOP_NUM_AXES(axis) { + TERN_(IS_KINEMATIC, sqr_stepper_space_mm += sq(dist[axis] * planner.mm_per_step[axis])); + if (distance_mm[axis]) { - const bool reverse = TEST(dm, axis); + const bool forward = dm[axis]; // When an axis changes direction, add axis backlash to the residual error - if (TEST(changed_dir, axis)) - residual_error[axis] += (reverse ? -f_corr : f_corr) * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis]; + if (changed_dir[axis]) + residual_error[axis] += (forward ? f_corr : -f_corr) * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis]; // Decide how much of the residual error to correct in this segment int32_t error_correction = residual_error[axis]; - if (reverse != (error_correction < 0)) - error_correction = 0; // Don't take up any backlash in this segment, as it would subtract steps #ifdef BACKLASH_SMOOTHING_MM if (error_correction && smoothing_mm != 0) { @@ -118,9 +124,18 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const } #endif + // Don't correct backlash in the opposite direction to movement on this axis and for accuracy in + // updating block->millimeters, don't add too many steps to the movement on this axis + if (forward) + LIMIT(error_correction, 0, dist[axis]); + else + LIMIT(error_correction, dist[axis], 0); + // This correction reduces the residual error and adds block steps if (error_correction) { + changed = true; block->steps[axis] += ABS(error_correction); + millimeters_delta += dist[axis] * error_correction * sq(planner.mm_per_step[axis]); #if ENABLED(CORE_BACKLASH) switch (axis) { case CORE_AXIS_1: @@ -142,22 +157,28 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const } } } + + // If backlash correction steps were added modify block->millimeters with a linear approximation + // See https://github.com/MarlinFirmware/Marlin/pull/26392 + if (changed) + block->millimeters += TERN(IS_KINEMATIC, millimeters_delta * block->millimeters / sqr_stepper_space_mm, millimeters_delta / block->millimeters); } int32_t Backlash::get_applied_steps(const AxisEnum axis) { if (axis >= NUM_AXES) return 0; - const bool reverse = TEST(last_direction_bits, axis); + const bool forward = last_direction_bits[axis]; const int32_t residual_error_axis = residual_error[axis]; - // At startup it is assumed the last move was forwards. So the applied - // steps will always be a non-positive number. + // At startup, when no steps are applied, it is assumed the last move was backwards. + // So the applied steps will always be zero (when moving backwards) or a positive + // number (when moving forwards). - if (!reverse) return -residual_error_axis; + if (!forward) return -residual_error_axis; const float f_corr = float(correction) / all_on; - const int32_t full_error_axis = -f_corr * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis]; + const int32_t full_error_axis = f_corr * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis]; return full_error_axis - residual_error_axis; } diff --git a/Marlin/src/feature/backlash.h b/Marlin/src/feature/backlash.h index 0bace526e5..b4790cb161 100644 --- a/Marlin/src/feature/backlash.h +++ b/Marlin/src/feature/backlash.h @@ -29,7 +29,7 @@ public: static constexpr uint8_t all_on = 0xFF, all_off = 0x00; private: - static axis_bits_t last_direction_bits; + static AxisBits last_direction_bits; static xyz_long_t residual_error; #if ENABLED(BACKLASH_GCODE) @@ -72,7 +72,7 @@ public: return has_measurement(X_AXIS) || has_measurement(Y_AXIS) || has_measurement(Z_AXIS); } - static void add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block); + static void add_correction_steps(const xyze_long_t &dist, const AxisBits dm, block_t * const block); static int32_t get_applied_steps(const AxisEnum axis); #if ENABLED(BACKLASH_GCODE) @@ -81,10 +81,10 @@ public: static void set_correction(const float v) { set_correction_uint8(_MAX(0, _MIN(1.0, v)) * all_on + 0.5f); } static float get_correction() { return float(get_correction_uint8()) / all_on; } static void set_distance_mm(const AxisEnum axis, const float v); - static float get_distance_mm(const AxisEnum axis) {return distance_mm[axis];} + static float get_distance_mm(const AxisEnum axis) { return distance_mm[axis]; } #ifdef BACKLASH_SMOOTHING_MM static void set_smoothing_mm(const float v); - static float get_smoothing_mm() {return smoothing_mm;} + static float get_smoothing_mm() { return smoothing_mm; } #endif #endif diff --git a/Marlin/src/feature/bedlevel/abl/bbl.cpp b/Marlin/src/feature/bedlevel/abl/bbl.cpp index be0e862cc1..918b06d2b4 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.cpp +++ b/Marlin/src/feature/bedlevel/abl/bbl.cpp @@ -133,8 +133,8 @@ void LevelingBilinear::extrapolate_unprobed_bed_level() { yend = ctry1; #endif - LOOP_LE_N(xo, xend) - LOOP_LE_N(yo, yend) { + for (uint8_t xo = 0; xo <= xend; ++xo) + for (uint8_t yo = 0; yo <= yend; ++yo) { uint8_t x2 = ctrx2 + xo, y2 = ctry2 + yo; #ifndef HALF_IN_X const uint8_t x1 = ctrx1 - xo; @@ -153,7 +153,7 @@ void LevelingBilinear::extrapolate_unprobed_bed_level() { } } -void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL*/) { +void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values/*=nullptr*/) { // print internal grid(s) or just the one passed as a parameter SERIAL_ECHOLNPGM("Bilinear Leveling Grid:"); print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 3, _z_values ? *_z_values[0] : z_values[0]); @@ -175,13 +175,13 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* xy_float_t LevelingBilinear::grid_factor_virt; #define LINEAR_EXTRAPOLATION(E, I) ((E) * 2 - (I)) - float LevelingBilinear::bed_level_virt_coord(const uint8_t x, const uint8_t y) { + float LevelingBilinear::virt_coord(const uint8_t x, const uint8_t y) { uint8_t ep = 0, ip = 1; if (x > (GRID_MAX_POINTS_X) + 1 || y > (GRID_MAX_POINTS_Y) + 1) { // The requested point requires extrapolating two points beyond the mesh. // These values are only requested for the edges of the mesh, which are always an actual mesh point, // and do not require interpolation. When interpolation is not needed, this "Mesh + 2" point is - // cancelled out in bed_level_virt_cmr and does not impact the result. Return 0.0 rather than + // cancelled out in virt_cmr and does not impact the result. Return 0.0 rather than // making this function more complex by extrapolating two points. return 0.0; } @@ -197,8 +197,8 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* ); else return LINEAR_EXTRAPOLATION( - bed_level_virt_coord(ep + 1, y), - bed_level_virt_coord(ip + 1, y) + virt_coord(ep + 1, y), + virt_coord(ip + 1, y) ); } if (!y || y == ABL_TEMP_POINTS_Y - 1) { @@ -213,14 +213,14 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* ); else return LINEAR_EXTRAPOLATION( - bed_level_virt_coord(x, ep + 1), - bed_level_virt_coord(x, ip + 1) + virt_coord(x, ep + 1), + virt_coord(x, ip + 1) ); } return z_values[x - 1][y - 1]; } - float LevelingBilinear::bed_level_virt_cmr(const float p[4], const uint8_t i, const float t) { + float LevelingBilinear::virt_cmr(const float p[4], const uint8_t i, const float t) { return ( p[i-1] * -t * sq(1 - t) + p[i] * (2 - 5 * sq(t) + 3 * t * sq(t)) @@ -229,33 +229,28 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* ) * 0.5f; } - float LevelingBilinear::bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty) { + float LevelingBilinear::virt_2cmr(const uint8_t x, const uint8_t y, const float tx, const float ty) { float row[4], column[4]; - LOOP_L_N(i, 4) { - LOOP_L_N(j, 4) { - column[j] = bed_level_virt_coord(i + x - 1, j + y - 1); + for (uint8_t i = 0; i < 4; ++i) { + for (uint8_t j = 0; j < 4; ++j) { + column[j] = virt_coord(i + x - 1, j + y - 1); } - row[i] = bed_level_virt_cmr(column, 1, ty); + row[i] = virt_cmr(column, 1, ty); } - return bed_level_virt_cmr(row, 1, tx); + return virt_cmr(row, 1, tx); } - void LevelingBilinear::bed_level_virt_interpolate() { + void LevelingBilinear::subdivide_mesh() { grid_spacing_virt = grid_spacing / (BILINEAR_SUBDIVISIONS); grid_factor_virt = grid_spacing_virt.reciprocal(); - LOOP_L_N(y, GRID_MAX_POINTS_Y) - LOOP_L_N(x, GRID_MAX_POINTS_X) - LOOP_L_N(ty, BILINEAR_SUBDIVISIONS) - LOOP_L_N(tx, BILINEAR_SUBDIVISIONS) { + for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; ++y) + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; ++x) + for (uint8_t ty = 0; ty < BILINEAR_SUBDIVISIONS; ++ty) + for (uint8_t tx = 0; tx < BILINEAR_SUBDIVISIONS; ++tx) { if ((ty && y == (GRID_MAX_POINTS_Y) - 1) || (tx && x == (GRID_MAX_POINTS_X) - 1)) continue; z_values_virt[x * (BILINEAR_SUBDIVISIONS) + tx][y * (BILINEAR_SUBDIVISIONS) + ty] = - bed_level_virt_2cmr( - x + 1, - y + 1, - (float)tx / (BILINEAR_SUBDIVISIONS), - (float)ty / (BILINEAR_SUBDIVISIONS) - ); + virt_2cmr(x + 1, y + 1, (float)tx / (BILINEAR_SUBDIVISIONS), (float)ty / (BILINEAR_SUBDIVISIONS)); } } @@ -263,7 +258,7 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* // Refresh after other values have been updated void LevelingBilinear::refresh_bed_level() { - TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); + TERN_(ABL_BILINEAR_SUBDIVISION, subdivide_mesh()); cached_rel.x = cached_rel.y = -999.999; cached_g.x = cached_g.y = -99; } @@ -374,7 +369,7 @@ float LevelingBilinear::get_z_correction(const xy_pos_t &raw) { * Prepare a bilinear-leveled linear move on Cartesian, * splitting the move where it crosses grid borders. */ - void LevelingBilinear::line_to_destination(const_feedRate_t scaled_fr_mm_s, uint16_t x_splits, uint16_t y_splits) { + void LevelingBilinear::line_to_destination(const feedRate_t scaled_fr_mm_s, uint16_t x_splits, uint16_t y_splits) { // Get current and destination cells for this line xy_int_t c1 { CELL_INDEX(x, current_position.x), CELL_INDEX(y, current_position.y) }, c2 { CELL_INDEX(x, destination.x), CELL_INDEX(y, destination.y) }; diff --git a/Marlin/src/feature/bedlevel/abl/bbl.h b/Marlin/src/feature/bedlevel/abl/bbl.h index c2be4fee82..fb890333dc 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.h +++ b/Marlin/src/feature/bedlevel/abl/bbl.h @@ -43,17 +43,17 @@ private: static xy_pos_t grid_spacing_virt; static xy_float_t grid_factor_virt; - static float bed_level_virt_coord(const uint8_t x, const uint8_t y); - static float bed_level_virt_cmr(const float p[4], const uint8_t i, const float t); - static float bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty); - static void bed_level_virt_interpolate(); + static float virt_coord(const uint8_t x, const uint8_t y); + static float virt_cmr(const float p[4], const uint8_t i, const float t); + static float virt_2cmr(const uint8_t x, const uint8_t y, const float tx, const float ty); + static void subdivide_mesh(); #endif public: static void reset(); static void set_grid(const xy_pos_t& _grid_spacing, const xy_pos_t& _grid_start); static void extrapolate_unprobed_bed_level(); - static void print_leveling_grid(const bed_mesh_t* _z_values = NULL); + static void print_leveling_grid(const bed_mesh_t *_z_values=nullptr); static void refresh_bed_level(); static bool has_mesh() { return !!grid_spacing.x; } static bool mesh_is_valid() { return has_mesh(); } @@ -63,7 +63,7 @@ public: 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); + static void line_to_destination(const feedRate_t scaled_fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF); #endif }; diff --git a/Marlin/src/feature/bedlevel/bdl/bdl.cpp b/Marlin/src/feature/bedlevel/bdl/bdl.cpp index 0668eb705c..45c7792d5c 100644 --- a/Marlin/src/feature/bedlevel/bdl/bdl.cpp +++ b/Marlin/src/feature/bedlevel/bdl/bdl.cpp @@ -24,7 +24,6 @@ #if ENABLED(BD_SENSOR) -#include "../../../MarlinCore.h" #include "../../../gcode/gcode.h" #include "../../../module/settings.h" #include "../../../module/motion.h" @@ -34,6 +33,7 @@ #include "../../../module/temperature.h" #include "../../../module/endstops.h" #include "../../babystep.h" +#include "../../../lcd/marlinui.h" // I2C software Master library for segment bed heating and bed distance sensor #include @@ -42,150 +42,214 @@ BDS_Leveling bdl; //#define DEBUG_OUT_BD +#define DEBUG_OUT ENABLED(DEBUG_OUT_BD) +#include "../../../core/debug_out.h" -// M102 S-5 Read raw Calibrate data -// M102 S-6 Start Calibrate -// M102 S4 Set the adjustable Z height value (e.g., 'M102 S4' means it will do adjusting while the Z height <= 0.4mm , disable with 'M102 S0'.) -// M102 S-1 Read sensor information +/** + * M102 S<#> : Set adjustable Z height in 0.1mm units (10ths of a mm) + * (e.g., 'M102 S4' enables adjusting for Z <= 0.4mm) + * M102 S0 : Disable adjustable Z height + * + * M102 S-1 : Read BDsensor version + * M102 S-2 : Read BDsensor distance value + * M102 S-5 : Read raw Calibration data + * M102 S-6 : Start Calibration + */ #define MAX_BD_HEIGHT 4.0f +#define CMD_READ_VERSION 1016 #define CMD_START_READ_CALIBRATE_DATA 1017 #define CMD_END_READ_CALIBRATE_DATA 1018 #define CMD_START_CALIBRATE 1019 #define CMD_END_CALIBRATE 1021 -#define CMD_READ_VERSION 1016 - -I2C_SegmentBED BD_I2C_SENSOR; - #define BD_SENSOR_I2C_ADDR 0x3C +I2C_SegmentBED BD_I2C_SENSOR; +float BDS_Leveling::pos_zero_offset; int8_t BDS_Leveling::config_state; -uint8_t BDS_Leveling::homing; - -void BDS_Leveling::echo_name() { SERIAL_ECHOPGM("Bed Distance Leveling"); } void BDS_Leveling::init(uint8_t _sda, uint8_t _scl, uint16_t delay_s) { - int ret = BD_I2C_SENSOR.i2c_init(_sda, _scl, BD_SENSOR_I2C_ADDR, delay_s); - if (ret != 1) SERIAL_ECHOLNPGM("BD_I2C_SENSOR Init Fail return code:", ret); - config_state = 0; + config_state = BDS_IDLE; + const int ret = BD_I2C_SENSOR.i2c_init(_sda, _scl, BD_SENSOR_I2C_ADDR, delay_s); + if (ret != 1) SERIAL_ECHOLNPGM("BD Sensor Init Fail (", ret, ")"); + sync_plan_position(); + pos_zero_offset = planner.get_axis_position_mm(Z_AXIS) - current_position.z; + SERIAL_ECHOLNPGM("BD Sensor Zero Offset:", pos_zero_offset); +} + +bool BDS_Leveling::check(const uint16_t data, const bool raw_data/*=false*/, const bool hicheck/*=false*/) { + if (BD_I2C_SENSOR.BD_Check_OddEven(data) == 0) { + SERIAL_ECHOLNPGM("Read Error."); + return true; // error + } + if (raw_data == true) { + if (hicheck && (data & 0x3FF) > 400) + SERIAL_ECHOLNPGM("Bad BD Sensor height! Recommended distance 0.5-2.0mm"); + else if (!good_data(data)) + SERIAL_ECHOLNPGM("Invalid data, please calibrate."); + else + return false; + } + else { + if ((data & 0x3FF) >= (MAX_BD_HEIGHT) * 100 - 10) + SERIAL_ECHOLNPGM("Out of Range."); + else + return false; + } + return true; // error +} + +float BDS_Leveling::interpret(const uint16_t data) { + return (data & 0x3FF) * 0.01f; } float BDS_Leveling::read() { - const uint16_t tmp = BD_I2C_SENSOR.BD_i2c_read(); - float BD_z = NAN; - if (BD_I2C_SENSOR.BD_Check_OddEven(tmp) && (tmp & 0x3FF) < 1020) - BD_z = (tmp & 0x3FF) / 100.0f; - return BD_z; + const uint16_t data = BD_I2C_SENSOR.BD_i2c_read(); + return check(data) ? NAN : interpret(data); } void BDS_Leveling::process() { - //if (config_state == 0) return; - static millis_t next_check_ms = 0; // starting at T=0 - static float z_pose = 0.0f; - const millis_t ms = millis(); - if (ELAPSED(ms, next_check_ms)) { // timed out (or first run) - next_check_ms = ms + (config_state < 0 ? 1000 : 100); // check at 1Hz or 10Hz - - unsigned short tmp = 0; - const float cur_z = planner.get_axis_position_mm(Z_AXIS); //current_position.z - static float old_cur_z = cur_z, - old_buf_z = current_position.z; + if (config_state == BDS_IDLE && marlin.printingIsActive()) return; + static millis_t next_check_ms = 0; // starting at T=0 + static float zpos = 0.0f; + const millis_t ms = millis(); + if (ELAPSED(ms, next_check_ms)) { // timed out (or first run) + // Check at 1KHz, 5Hz, or 20Hz + next_check_ms = ms + (config_state == BDS_HOMING_Z ? 1 : (config_state < BDS_IDLE ? 200 : 50)); + uint16_t tmp = 0; + const float cur_z = planner.get_axis_position_mm(Z_AXIS) - pos_zero_offset; + static float old_cur_z = cur_z, old_buf_z = current_position.z; tmp = BD_I2C_SENSOR.BD_i2c_read(); - if (BD_I2C_SENSOR.BD_Check_OddEven(tmp) && (tmp & 0x3FF) < 1020) { - const float z_sensor = (tmp & 0x3FF) / 100.0f; - if (cur_z < 0) config_state = 0; - //float abs_z = current_position.z > cur_z ? (current_position.z - cur_z) : (cur_z - current_position.z); - if ( cur_z < config_state * 0.1f - && config_state > 0 - && old_cur_z == cur_z - && old_buf_z == current_position.z - && z_sensor < (MAX_BD_HEIGHT) - ) { - babystep.set_mm(Z_AXIS, cur_z - z_sensor); - #if ENABLED(DEBUG_OUT_BD) - SERIAL_ECHOLNPGM("BD:", z_sensor, ", Z:", cur_z, "|", current_position.z); - #endif - } - else { - babystep.set_mm(Z_AXIS, 0); - //if (old_cur_z <= cur_z) Z_DIR_WRITE(!INVERT_Z_DIR); - stepper.set_directions(); - } + if (BD_I2C_SENSOR.BD_Check_OddEven(tmp) && good_data(tmp)) { + const float z_sensor = interpret(tmp); + #if ENABLED(BABYSTEPPING) + if (config_state > 0) { + if (cur_z < config_state * 0.1f + && old_cur_z == cur_z + && old_buf_z == current_position.z + && z_sensor < (MAX_BD_HEIGHT) - 0.1f + ) { + babystep.set_mm(Z_AXIS, cur_z - z_sensor); + DEBUG_ECHOLNPGM("BD:", z_sensor, ", Z:", cur_z, "|", current_position.z); + } + else + babystep.set_mm(Z_AXIS, 0); + } + #endif + old_cur_z = cur_z; old_buf_z = current_position.z; - endstops.bdp_state_update(z_sensor <= 0.01f); - //endstops.update(); + endstops.bdp_state_update(z_sensor <= BD_SENSOR_HOME_Z_POSITION); + + #if HAS_STATUS_MESSAGE + static float old_z_sensor = 0; + if (old_z_sensor != z_sensor) { + old_z_sensor = z_sensor; + char tmp_1[32]; + sprintf_P(tmp_1, PSTR("BD:%d.%02dmm"), int(z_sensor), int(z_sensor * 100) % 100); + //SERIAL_ECHOLNPGM("Bed Dis:", z_sensor, "mm"); + ui.set_status(tmp_1, true); + } + #endif + } + else if (config_state == BDS_HOMING_Z) { + SERIAL_ECHOLNPGM("Read:", tmp); + marlin.kill(F("BDsensor connect Err!")); } - else - stepper.set_directions(); - #if ENABLED(DEBUG_OUT_BD) - SERIAL_ECHOLNPGM("BD:", tmp & 0x3FF, ", Z:", cur_z, "|", current_position.z); - if (BD_I2C_SENSOR.BD_Check_OddEven(tmp) == 0) SERIAL_ECHOLNPGM("errorCRC"); - #endif + DEBUG_ECHOLNPGM("BD:", tmp & 0x3FF, " Z:", cur_z, "|", current_position.z); + if (TERN0(DEBUG_OUT_BD, BD_I2C_SENSOR.BD_Check_OddEven(tmp) == 0)) DEBUG_ECHOLNPGM("CRC error"); - if ((tmp & 0x3FF) > 1020) { + if (!good_data(tmp)) { BD_I2C_SENSOR.BD_i2c_stop(); safe_delay(10); } + // Read version. Usually used as a connection check + if (config_state == BDS_VERSION) { + config_state = BDS_IDLE; + BD_I2C_SENSOR.BD_i2c_write(CMD_READ_VERSION); + safe_delay(100); + char tmp_1[21]; + for (int i = 0; i < 19; i++) { + tmp_1[i] = BD_I2C_SENSOR.BD_i2c_read() & 0xFF; + safe_delay(50); + } + BD_I2C_SENSOR.BD_i2c_write(CMD_END_READ_CALIBRATE_DATA); + SERIAL_ECHOLNPGM("BD Sensor version:", tmp_1); + if (tmp_1[0] != 'V') SERIAL_ECHOLNPGM("Read Error. Check connection and delay."); + safe_delay(50); + } // read raw calibrate data - if (config_state == -5) { + else if (config_state == BDS_READ_RAW) { BD_I2C_SENSOR.BD_i2c_write(CMD_START_READ_CALIBRATE_DATA); - safe_delay(1000); + safe_delay(100); for (int i = 0; i < MAX_BD_HEIGHT * 10; i++) { tmp = BD_I2C_SENSOR.BD_i2c_read(); - SERIAL_ECHOLNPGM("Calibrate data:", i, ",", tmp & 0x3FF, ", check:", BD_I2C_SENSOR.BD_Check_OddEven(tmp)); - safe_delay(500); + SERIAL_ECHOLNPGM("Calibrate data:", i, ",", tmp & 0x3FF); + (void)check(tmp, true, i == 0); + safe_delay(50); } - config_state = 0; BD_I2C_SENSOR.BD_i2c_write(CMD_END_READ_CALIBRATE_DATA); - safe_delay(500); + safe_delay(50); + config_state = BDS_IDLE; } - else if (config_state <= -6) { // Start Calibrate - safe_delay(100); - if (config_state == -6) { - //BD_I2C_SENSOR.BD_i2c_write(1019); // begin calibrate - //delay(1000); - gcode.stepper_inactive_time = SEC_TO_MS(60 * 5); - gcode.process_subcommands_now(F("M17 Z")); - gcode.process_subcommands_now(F("G1 Z0.0")); - z_pose = 0; - safe_delay(1000); + else if (config_state <= BDS_CALIBRATE_START) { // Start Calibrate + safe_delay(10); + if (config_state == BDS_CALIBRATE_START) { + config_state = BDS_CALIBRATING; + REMEMBER(gsit, gcode.stepper_inactive_time, MIN_TO_MS(5)); + SERIAL_ECHOLNPGM("c_z0:", planner.get_axis_position_mm(Z_AXIS), "-", pos_zero_offset); + + // Move the z axis instead of enabling the Z axis with M17 + // TODO: Use do_blocking_move_to_z for synchronized move. + current_position.z = 0; + sync_plan_position(); + gcode.process_subcommands_now(F("G1Z0.05")); + safe_delay(300); + gcode.process_subcommands_now(F("G1Z0.00")); + safe_delay(300); + current_position.z = 0; + sync_plan_position(); + //safe_delay(1000); + + while ((planner.get_axis_position_mm(Z_AXIS) - pos_zero_offset) > 0.00001f) { + safe_delay(200); + SERIAL_ECHOLNPGM("waiting cur_z:", planner.get_axis_position_mm(Z_AXIS)); + } + zpos = 0.00001f; + safe_delay(100); BD_I2C_SENSOR.BD_i2c_write(CMD_START_CALIBRATE); // Begin calibrate - SERIAL_ECHOLNPGM("Begin calibrate"); - safe_delay(2000); - config_state = -7; + SERIAL_ECHOLNPGM("BD Sensor Calibrating..."); + safe_delay(200); } - else if (planner.get_axis_position_mm(Z_AXIS) < 10.0f) { - if (z_pose >= MAX_BD_HEIGHT) { + else if ((planner.get_axis_position_mm(Z_AXIS) - pos_zero_offset) < 10.0f) { + if (zpos >= MAX_BD_HEIGHT) { + config_state = BDS_IDLE; BD_I2C_SENSOR.BD_i2c_write(CMD_END_CALIBRATE); // End calibrate - SERIAL_ECHOLNPGM("End calibrate data"); - z_pose = 7; - config_state = 0; - safe_delay(1000); + SERIAL_ECHOLNPGM("BD Sensor calibrated."); + zpos = 7.0f; + safe_delay(500); } else { - float tmp_k = 0; - char tmp_1[30]; - sprintf_P(tmp_1, PSTR("G1 Z%d.%d"), int(z_pose), int(int(z_pose * 10) % 10)); + char tmp_1[32]; + // TODO: Use prepare_internal_move_to_destination to guarantee machine space + sprintf_P(tmp_1, PSTR("G1Z%d.%d"), int(zpos), int(zpos * 10) % 10); gcode.process_subcommands_now(tmp_1); - - SERIAL_ECHO(tmp_1); - SERIAL_ECHOLNPGM(" ,Z:", current_position.z); - - while (tmp_k < (z_pose - 0.1f)) { - tmp_k = planner.get_axis_position_mm(Z_AXIS); - safe_delay(1); + SERIAL_ECHO(tmp_1); SERIAL_ECHOLNPGM(", Z:", current_position.z); + uint16_t failcount = 300; + for (float tmp_k = 0; abs(zpos - tmp_k) > 0.006f && failcount--;) { + tmp_k = planner.get_axis_position_mm(Z_AXIS) - pos_zero_offset; + safe_delay(10); + if (!failcount--) break; } - safe_delay(800); - tmp = (z_pose + 0.0001f) * 10; + safe_delay(600); + tmp = uint16_t((zpos + 0.00001f) * 10); BD_I2C_SENSOR.BD_i2c_write(tmp); - SERIAL_ECHOLNPGM("w:", tmp, ",Zpose:", z_pose); - z_pose += 0.1001f; - //queue.enqueue_now_P(PSTR("G90")); + SERIAL_ECHOLNPGM("w:", tmp, ", Z:", zpos); + zpos += 0.1001f; } } } diff --git a/Marlin/src/feature/bedlevel/bdl/bdl.h b/Marlin/src/feature/bedlevel/bdl/bdl.h index 6307b1ab28..ed91d7081b 100644 --- a/Marlin/src/feature/bedlevel/bdl/bdl.h +++ b/Marlin/src/feature/bedlevel/bdl/bdl.h @@ -23,14 +23,30 @@ #include +#ifndef BD_SENSOR_HOME_Z_POSITION + #define BD_SENSOR_HOME_Z_POSITION 0.5 +#endif + +enum BDS_State : int8_t { + BDS_IDLE, + BDS_VERSION = -1, + BDS_READ_MM = -2, + BDS_HOMING_Z = -3, + BDS_READ_RAW = -5, + BDS_CALIBRATE_START = -6, + BDS_CALIBRATING = -7 +}; + class BDS_Leveling { public: static int8_t config_state; - static uint8_t homing; - static void echo_name(); + static float pos_zero_offset; static void init(uint8_t _sda, uint8_t _scl, uint16_t delay_s); static void process(); static float read(); + static float interpret(const uint16_t data); + static float good_data(const uint16_t data) { return (data & 0x3FF) < 1016; } + static bool check(const uint16_t data, const bool raw_data=false, const bool hicheck=false); }; extern BDS_Leveling bdl; diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index 2207884c36..e479e4c70a 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -27,7 +27,7 @@ #include "bedlevel.h" #include "../../module/planner.h" -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) #include "../../module/motion.h" #endif @@ -57,6 +57,7 @@ bool leveling_is_valid() { * Enable: Current position = "unleveled" physical position */ void set_bed_leveling_enabled(const bool enable/*=true*/) { + DEBUG_SECTION(log_sble, "set_bed_leveling_enabled", DEBUGGING(LEVELING)); const bool can_change = TERN1(AUTO_BED_LEVELING_BILINEAR, !enable || leveling_is_valid()); @@ -75,9 +76,9 @@ void set_bed_leveling_enabled(const bool enable/*=true*/) { planner.synchronize(); // 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 + planner.apply_modifiers(current_position, true); // Physical position with all modifiers + FLIP(planner.leveling_active); // Toggle leveling between apply and unapply + planner.unapply_modifiers(current_position, true); // Logical position with modifiers removed sync_plan_position(); _report_leveling(); @@ -90,7 +91,7 @@ TemporaryBedLevelingState::TemporaryBedLevelingState(const bool enable) : saved( #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - void set_z_fade_height(const_float_t zfh, const bool do_report/*=true*/) { + void set_z_fade_height(const float zfh, const bool do_report/*=true*/) { if (planner.z_fade_height == zfh) return; @@ -119,7 +120,7 @@ void reset_bed_level() { TERN_(ABL_PLANAR, planner.bed_level_matrix.set_to_identity()); } -#if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) +#if ANY(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) /** * Enable to produce output in JSON format suitable @@ -136,8 +137,8 @@ void reset_bed_level() { */ void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, const float *values) { #ifndef SCAD_MESH_OUTPUT - LOOP_L_N(x, sx) { - serial_spaces(precision + (x < 10 ? 3 : 2)); + for (uint8_t x = 0; x < sx; ++x) { + SERIAL_ECHO_SP(precision + (x < 10 ? 3 : 2)); SERIAL_ECHO(x); } SERIAL_EOL(); @@ -145,19 +146,19 @@ void reset_bed_level() { #ifdef SCAD_MESH_OUTPUT SERIAL_ECHOLNPGM("measured_z = ["); // open 2D array #endif - LOOP_L_N(y, sy) { + for (uint8_t y = 0; y < sy; ++y) { #ifdef SCAD_MESH_OUTPUT SERIAL_ECHOPGM(" ["); // open sub-array #else if (y < 10) SERIAL_CHAR(' '); SERIAL_ECHO(y); #endif - LOOP_L_N(x, sx) { + for (uint8_t x = 0; x < sx; ++x) { SERIAL_CHAR(' '); const float offset = values[x * sy + y]; if (!isnan(offset)) { if (offset >= 0) SERIAL_CHAR('+'); - SERIAL_ECHO_F(offset, int(precision)); + SERIAL_ECHO(p_float_t(offset, precision)); } else { #ifdef SCAD_MESH_OUTPUT @@ -165,7 +166,7 @@ void reset_bed_level() { SERIAL_CHAR(' '); SERIAL_ECHOPGM("NAN"); #else - LOOP_L_N(i, precision + 3) + for (uint8_t i = 0; i < precision + 3; ++i) SERIAL_CHAR(i ? '=' : ' '); #endif } @@ -187,7 +188,7 @@ void reset_bed_level() { #endif // AUTO_BED_LEVELING_BILINEAR || MESH_BED_LEVELING -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) void _manual_goto_xy(const xy_pos_t &pos) { diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index aeafec10d6..5bfa2b7faf 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EITHER(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) +#if ANY(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) #define CAN_SET_LEVELING_AFTER_G28 1 #endif @@ -38,10 +38,10 @@ void set_bed_leveling_enabled(const bool enable=true); void reset_bed_level(); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - void set_z_fade_height(const_float_t zfh, const bool do_report=true); + void set_z_fade_height(const float zfh, const bool do_report=true); #endif -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) void _manual_goto_xy(const xy_pos_t &pos); #endif @@ -69,7 +69,7 @@ class TemporaryBedLevelingState { #include "mbl/mesh_bed_leveling.h" #endif - #if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) + #if ANY(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) #include diff --git a/Marlin/src/feature/bedlevel/hilbert_curve.cpp b/Marlin/src/feature/bedlevel/hilbert_curve.cpp index 7474123e3f..57cbdfb34d 100644 --- a/Marlin/src/feature/bedlevel/hilbert_curve.cpp +++ b/Marlin/src/feature/bedlevel/hilbert_curve.cpp @@ -28,8 +28,8 @@ constexpr int8_t to_fix(int8_t v) { return v * 2; } constexpr int8_t to_int(int8_t v) { return v / 2; } -constexpr uint8_t log2(uint8_t n) { return (n > 1) ? 1 + log2(n >> 1) : 0; } -constexpr uint8_t order(uint8_t n) { return uint8_t(log2(n - 1)) + 1; } +constexpr uint8_t log2(uint8_t n) { return (n > 1) ? 1 + log2(uint8_t(n >> 1)) : 0; } +constexpr uint8_t order(uint8_t n) { return uint8_t(log2(uint8_t(n - 1))) + 1; } constexpr uint8_t ord = order(_MAX(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y)); constexpr uint8_t dim = _BV(ord); diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp index 193cbbf765..155d34c4df 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp @@ -40,9 +40,9 @@ mesh_bed_leveling::index_to_ypos[GRID_MAX_POINTS_Y]; mesh_bed_leveling::mesh_bed_leveling() { - LOOP_L_N(i, GRID_MAX_POINTS_X) + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) index_to_xpos[i] = MESH_MIN_X + i * (MESH_X_DIST); - LOOP_L_N(i, GRID_MAX_POINTS_Y) + for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; ++i) index_to_ypos[i] = MESH_MIN_Y + i * (MESH_Y_DIST); reset(); } @@ -61,9 +61,9 @@ * Prepare a mesh-leveled linear move in a Cartesian setup, * splitting the move where it crosses mesh borders. */ - void mesh_bed_leveling::line_to_destination(const_feedRate_t scaled_fr_mm_s, uint8_t x_splits, uint8_t y_splits) { + void mesh_bed_leveling::line_to_destination(const feedRate_t scaled_fr_mm_s, uint8_t x_splits, uint8_t y_splits) { // Get current and destination cells for this line - xy_int8_t scel = cell_indexes(current_position), ecel = cell_indexes(destination); + xy_uint8_t scel = cell_indexes(current_position), ecel = cell_indexes(destination); NOMORE(scel.x, GRID_MAX_CELLS_X - 1); NOMORE(scel.y, GRID_MAX_CELLS_Y - 1); NOMORE(ecel.x, GRID_MAX_CELLS_X - 1); @@ -80,7 +80,7 @@ float normalized_dist; xyze_pos_t dest; - const int8_t gcx = _MAX(scel.x, ecel.x), gcy = _MAX(scel.y, ecel.y); + const uint8_t gcx = _MAX(scel.x, ecel.x), gcy = _MAX(scel.y, ecel.y); // Crosses on the X and not already split on this X? // The x_splits flags are insurance against rounding errors. @@ -123,8 +123,7 @@ #endif // IS_CARTESIAN && !SEGMENT_LEVELED_MOVES void mesh_bed_leveling::report_mesh() { - SERIAL_ECHOPAIR_F(STRINGIFY(GRID_MAX_POINTS_X) "x" STRINGIFY(GRID_MAX_POINTS_Y) " mesh. Z offset: ", z_offset, 5); - SERIAL_ECHOLNPGM("\nMeasured points:"); + SERIAL_ECHOLN(F(STRINGIFY(GRID_MAX_POINTS_X) "x" STRINGIFY(GRID_MAX_POINTS_Y) " mesh. Z offset: "), p_float_t(z_offset, 5), F("\nMeasured points:")); print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 5, z_values[0]); } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index 1a8e693e81..43dabd3adb 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -32,8 +32,8 @@ enum MeshLevelingState : char { MeshReset // G29 S5 }; -#define MESH_X_DIST (float(MESH_MAX_X - (MESH_MIN_X)) / (GRID_MAX_CELLS_X)) -#define MESH_Y_DIST (float(MESH_MAX_Y - (MESH_MIN_Y)) / (GRID_MAX_CELLS_Y)) +#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)) class mesh_bed_leveling { public: @@ -55,7 +55,7 @@ public: 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 set_z(const int8_t px, const int8_t py, const float z) { z_values[px][py] = z; } static void zigzag(const int8_t index, int8_t &px, int8_t &py) { px = index % (GRID_MAX_POINTS_X); @@ -63,7 +63,7 @@ public: if (py & 1) px = (GRID_MAX_POINTS_X) - 1 - px; // Zig zag } - static void set_zigzag_z(const int8_t index, const_float_t z) { + static void set_zigzag_z(const int8_t index, const float z) { int8_t px, py; zigzag(index, px, py); set_z(px, py, z); @@ -72,33 +72,33 @@ public: static float get_mesh_x(const uint8_t i) { return index_to_xpos[i]; } static float get_mesh_y(const uint8_t i) { return index_to_ypos[i]; } - static int8_t cell_index_x(const_float_t x) { + static uint8_t cell_index_x(const float x) { int8_t cx = (x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST); return constrain(cx, 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y(const_float_t y) { + static uint8_t cell_index_y(const float y) { int8_t cy = (y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST); return constrain(cy, 0, GRID_MAX_CELLS_Y - 1); } - static xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + static xy_uint8_t cell_indexes(const float x, const float y) { return { cell_index_x(x), cell_index_y(y) }; } - static xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + static xy_uint8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } - static int8_t probe_index_x(const_float_t x) { + static int8_t probe_index_x(const float x) { int8_t px = (x - (MESH_MIN_X) + 0.5f * (MESH_X_DIST)) * RECIPROCAL(MESH_X_DIST); return WITHIN(px, 0, (GRID_MAX_POINTS_X) - 1) ? px : -1; } - static int8_t probe_index_y(const_float_t y) { + static int8_t probe_index_y(const float y) { int8_t py = (y - (MESH_MIN_Y) + 0.5f * (MESH_Y_DIST)) * RECIPROCAL(MESH_Y_DIST); return WITHIN(py, 0, (GRID_MAX_POINTS_Y) - 1) ? py : -1; } - static xy_int8_t probe_indexes(const_float_t x, const_float_t y) { + static xy_int8_t probe_indexes(const float x, const float y) { return { probe_index_x(x), probe_index_y(y) }; } static xy_int8_t probe_indexes(const xy_pos_t &xy) { return probe_indexes(xy.x, xy.y); } - static float calc_z0(const_float_t a0, const_float_t a1, const_float_t z1, const_float_t a2, const_float_t z2) { + static float calc_z0(const float a0, const float a1, const float z1, const float a2, const float z2) { const float delta_z = (z2 - z1) / (a2 - a1), delta_a = a0 - a1; return z1 + delta_a * delta_z; @@ -107,9 +107,9 @@ public: static float get_z_offset() { return z_offset; } static float get_z_correction(const xy_pos_t &pos) { - const xy_int8_t ind = cell_indexes(pos); + const xy_uint8_t ind = cell_indexes(pos); const float x1 = index_to_xpos[ind.x], x2 = index_to_xpos[ind.x+1], - y1 = index_to_xpos[ind.y], y2 = index_to_xpos[ind.y+1], + y1 = index_to_ypos[ind.y], y2 = index_to_ypos[ind.y+1], z1 = calc_z0(pos.x, x1, z_values[ind.x][ind.y ], x2, z_values[ind.x+1][ind.y ]), 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); @@ -118,7 +118,7 @@ public: } #if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES) - static void line_to_destination(const_feedRate_t scaled_fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF); + static void line_to_destination(const feedRate_t scaled_fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF); #endif }; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 2aa50be34d..2357437633 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -28,7 +28,6 @@ unified_bed_leveling bedlevel; -#include "../../../MarlinCore.h" #include "../../../gcode/gcode.h" #include "../../../module/settings.h" @@ -51,15 +50,14 @@ void unified_bed_leveling::report_current_mesh() { GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { SERIAL_ECHO_START(); - SERIAL_ECHOPGM(" M421 I", x, " J", y); - SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); + SERIAL_ECHOLN(F(" M421 I"), x, F(" J"), y, FPSTR(SP_Z_STR), p_float_t(z_values[x][y], 4)); serial_delay(75); // Prevent Printrun from exploding } } void unified_bed_leveling::report_state() { echo_name(); - SERIAL_ECHO_TERNARY(planner.leveling_active, " System v" UBL_VERSION " ", "", "in", "active\n"); + serial_ternary(F(" System v" UBL_VERSION " "), planner.leveling_active, nullptr, F("in"), F("active\n")); serial_delay(50); } @@ -103,7 +101,7 @@ void unified_bed_leveling::invalidate() { set_all_mesh_points_to_value(NAN); } -void unified_bed_leveling::set_all_mesh_points_to_value(const_float_t value) { +void unified_bed_leveling::set_all_mesh_points_to_value(const float value) { GRID_LOOP(x, y) { z_values[x][y] = value; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, value)); @@ -116,7 +114,7 @@ void unified_bed_leveling::set_all_mesh_points_to_value(const_float_t value) { constexpr int16_t Z_STEPS_NAN = INT16_MAX; void unified_bed_leveling::set_store_from_mesh(const bed_mesh_t &in_values, mesh_store_t &stored_values) { - auto z_to_store = [](const_float_t z) { + auto z_to_store = [](const float z) { if (isnan(z)) return Z_STEPS_NAN; const int32_t z_scaled = TRUNC(z * mesh_store_scaling); if (z_scaled == Z_STEPS_NAN || !WITHIN(z_scaled, INT16_MIN, INT16_MAX)) @@ -149,7 +147,7 @@ static void serial_echo_xy(const uint8_t sp, const int16_t x, const int16_t y) { static void serial_echo_column_labels(const uint8_t sp) { SERIAL_ECHO_SP(7); - LOOP_L_N(i, GRID_MAX_POINTS_X) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { if (i < 10) SERIAL_CHAR(' '); SERIAL_ECHO(i); SERIAL_ECHO_SP(sp); @@ -199,7 +197,7 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { } // Row Values (I indexes) - LOOP_L_N(i, GRID_MAX_POINTS_X) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { // Opening Brace or Space const bool is_current = i == curr.x && j == curr.y; @@ -211,10 +209,10 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { // TODO: Display on Graphical LCD } else if (isnan(f)) - SERIAL_ECHOF(human ? F(" . ") : F("NAN")); + SERIAL_ECHO(human ? F(" . ") : F("NAN")); else if (human || csv) { if (human && f >= 0) SERIAL_CHAR(f > 0 ? '+' : ' '); // Display sign also for positive numbers (' ' for 0) - SERIAL_DECIMAL(f); // Positive: 5 digits, Negative: 6 digits + SERIAL_ECHO(p_float_t(f, 3)); // Positive: 5 digits, Negative: 6 digits } if (csv && i < (GRID_MAX_POINTS_X) - 1) SERIAL_CHAR('\t'); @@ -222,7 +220,7 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { if (human) SERIAL_CHAR(is_current ? ']' : ' '); SERIAL_FLUSHTX(); - idle_no_sleep(); + marlin.idle_no_sleep(); } if (!lcd) SERIAL_EOL(); @@ -260,7 +258,7 @@ bool unified_bed_leveling::sanity_check() { */ void GcodeSuite::M1004() { - #define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34", "") + #define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34\n", "") #define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R") #if HAS_HOTEND @@ -280,7 +278,7 @@ bool unified_bed_leveling::sanity_check() { #endif process_subcommands_now(FPSTR(G28_STR)); // Home - process_subcommands_now(F(ALIGN_GCODE "\n" // Align multi z axis if available + process_subcommands_now(F(ALIGN_GCODE // Align multi z axis if available PROBE_GCODE "\n" // Build mesh with available hardware "G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index a7103d6e18..f6e9ba0cd9 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -38,8 +38,8 @@ enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP, CLOSEST }; struct mesh_index_pair; -#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 MESH_X_DIST (float((MESH_MAX_X) - (MESH_MIN_X)) / (GRID_MAX_CELLS_X)) +#define MESH_Y_DIST (float((MESH_MAX_Y) - (MESH_MIN_Y)) / (GRID_MAX_CELLS_Y)) #if ENABLED(OPTIMIZED_MESH_STORAGE) typedef int16_t mesh_store_t[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; @@ -48,8 +48,8 @@ struct mesh_index_pair; typedef struct { bool C_seen; int8_t KLS_storage_slot; - uint8_t R_repetition, - V_verbosity, + grid_count_t R_repetition; + uint8_t V_verbosity, P_phase, T_map_type; float B_shim_thickness, @@ -67,17 +67,16 @@ private: static G29_parameters_t param; #if IS_NEWPANEL - static void move_z_with_encoder(const_float_t multiplier); + static void move_z_with_encoder(const float 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 manually_probe_remaining_mesh(const xy_pos_t&, const float, const float, const bool) __O0; static void fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) __O0; #endif static bool G29_parse_parameters() __O0; - static void shift_mesh_height(); + static void shift_mesh_height(const float zoffs); 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) { @@ -96,19 +95,19 @@ public: static void report_current_mesh(); static void report_state(); static void save_ubl_active_state_and_disable(); - static void restore_ubl_active_state_and_leave(); + static void restore_ubl_active_state(const bool is_done=true); 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 void set_all_mesh_points_to_value(const float value); + static void adjust_mesh_to_mean(const bool cflag, const float value); static bool sanity_check(); static void 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 smart_fill_wlsf(const float ) __O2; // O2 gives smaller code than Os on A2560 static int8_t storage_slot; @@ -131,42 +130,42 @@ public: unified_bed_leveling(); - FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const_float_t z) { z_values[px][py] = z; } + FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float z) { z_values[px][py] = z; } - static int8_t cell_index_x_raw(const_float_t x) { + static int8_t cell_index_x_raw(const float x) { return FLOOR((x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST)); } - static int8_t cell_index_y_raw(const_float_t y) { + static int8_t cell_index_y_raw(const float y) { return FLOOR((y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST)); } - static int8_t cell_index_x_valid(const_float_t x) { + static bool cell_index_x_valid(const float x) { return WITHIN(cell_index_x_raw(x), 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y_valid(const_float_t y) { + static bool cell_index_y_valid(const float y) { return WITHIN(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); } - static int8_t cell_index_x(const_float_t x) { + static uint8_t cell_index_x(const float x) { return constrain(cell_index_x_raw(x), 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y(const_float_t y) { + static uint8_t cell_index_y(const float y) { return constrain(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); } - static xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + static xy_uint8_t cell_indexes(const float x, const float y) { return { cell_index_x(x), cell_index_y(y) }; } - static xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + static xy_uint8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } - static int8_t closest_x_index(const_float_t x) { + static int8_t closest_x_index(const float x) { const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * RECIPROCAL(MESH_X_DIST); return WITHIN(px, 0, (GRID_MAX_POINTS_X) - 1) ? px : -1; } - static int8_t closest_y_index(const_float_t y) { + static int8_t closest_y_index(const float y) { const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * RECIPROCAL(MESH_Y_DIST); return WITHIN(py, 0, (GRID_MAX_POINTS_Y) - 1) ? py : -1; } @@ -189,7 +188,7 @@ public: * It is fairly expensive with its 4 floating point additions and 2 floating point * multiplications. */ - FORCE_INLINE static float calc_z0(const_float_t a0, const_float_t a1, const_float_t z1, const_float_t a2, const_float_t z2) { + FORCE_INLINE static float calc_z0(const float a0, const float a1, const float z1, const float a2, const float z2) { return z1 + (z2 - z1) * (a0 - a1) / (a2 - a1); } @@ -203,7 +202,7 @@ public: * z_correction_for_x_on_horizontal_mesh_line is an optimization for * the case where the printer is making a vertical line that only crosses horizontal mesh lines. */ - static float z_correction_for_x_on_horizontal_mesh_line(const_float_t rx0, const int x1_i, const int yi) { + static float z_correction_for_x_on_horizontal_mesh_line(const float rx0, const int x1_i, const int yi) { if (!WITHIN(x1_i, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(yi, 0, (GRID_MAX_POINTS_Y) - 1)) { if (DEBUGGING(LEVELING)) { @@ -226,7 +225,7 @@ public: // // See comments above for z_correction_for_x_on_horizontal_mesh_line // - static float z_correction_for_y_on_vertical_mesh_line(const_float_t ry0, const int xi, const int y1_i) { + static float z_correction_for_y_on_vertical_mesh_line(const float ry0, const int xi, const int y1_i) { if (!WITHIN(xi, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(y1_i, 0, (GRID_MAX_POINTS_Y) - 1)) { if (DEBUGGING(LEVELING)) { @@ -252,7 +251,7 @@ public: * Z-Height at both ends. Then it does a linear interpolation of these heights based * on the Y position within the cell. */ - static float get_z_correction(const_float_t rx0, const_float_t ry0) { + static float get_z_correction(const float rx0, const float ry0) { const int8_t cx = cell_index_x(rx0), cy = cell_index_y(ry0); // return values are clamped /** @@ -264,9 +263,9 @@ public: 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, - 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]), + const uint8_t mx = _MIN(cx, (GRID_MAX_POINTS_X) - 2) + 1, my = _MIN(cy, (GRID_MAX_POINTS_Y) - 2) + 1; + const float x0 = get_mesh_x(cx), x1 = get_mesh_x(cx + 1), + 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); @@ -279,10 +278,8 @@ public: if (DEBUGGING(MESH_ADJUST)) DEBUG_ECHOLNPGM("??? Yikes! NAN in "); } - if (DEBUGGING(MESH_ADJUST)) { - DEBUG_ECHOPGM("get_z_correction(", rx0, ", ", ry0); - DEBUG_ECHOLNPAIR_F(") => ", z0, 6); - } + if (DEBUGGING(MESH_ADJUST)) + DEBUG_ECHOLN(F("get_z_correction("), rx0, F(", "), ry0, F(") => "), p_float_t(z0, 6)); return z0; } @@ -298,9 +295,9 @@ public: } #if UBL_SEGMENTED - static bool line_to_destination_segmented(const_feedRate_t scaled_fr_mm_s); + static bool line_to_destination_segmented(const feedRate_t scaled_fr_mm_s); #else - static void line_to_destination_cartesian(const_feedRate_t scaled_fr_mm_s, const uint8_t e); + static void line_to_destination_cartesian(const feedRate_t scaled_fr_mm_s, const uint8_t e); #endif static bool mesh_is_valid() { diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index f1e88006ff..6341933bfb 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -26,7 +26,6 @@ #include "../bedlevel.h" -#include "../../../MarlinCore.h" #include "../../../HAL/shared/eeprom_api.h" #include "../../../libs/hex_print.h" #include "../../../module/settings.h" @@ -37,10 +36,6 @@ #include "../../../gcode/gcode.h" #include "../../../libs/least_squares_fit.h" -#if HAS_MULTI_HOTEND - #include "../../../module/tool_change.h" -#endif - #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../../core/debug_out.h" @@ -52,6 +47,10 @@ #include "../hilbert_curve.h" #endif +#if ENABLED(FT_MOTION) + #include "../../../module/ft_motion.h" +#endif + #include #define UBL_G29_P31 @@ -112,7 +111,7 @@ * If omitted, the nozzle will raise by Z_CLEARANCE_BETWEEN_PROBES. * * H # Offset With P4, 'H' specifies the Offset above the mesh height to place the nozzle. - * If omitted, Z_CLEARANCE_BETWEEN_PROBES will be used. + * If omitted, Z_TWEEN_SAFE_CLEARANCE will be used. * * I # Invalidate Invalidate the specified number of Mesh Points near the given 'X' 'Y'. If X or Y are omitted, * the nozzle location is used. If no 'I' value is given, only the point nearest to the location @@ -301,26 +300,41 @@ G29_parameters_t unified_bed_leveling::param; void unified_bed_leveling::G29() { - bool probe_deployed = false; + #ifdef EVENT_GCODE_AFTER_G29 + bool probe_deployed = false; + #define SET_PROBE_DEPLOYED(N) probe_deployed = N + #else + #define SET_PROBE_DEPLOYED(N) + #endif + if (G29_parse_parameters()) return; // Abort on parameter error const uint8_t p_val = parser.byteval('P'); const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J'); - #if HAS_MULTI_HOTEND - const uint8_t old_tool_index = active_extruder; - #endif + + // Potentially disable Fixed-Time Motion for probing + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); // Check for commands that require the printer to be homed if (may_move) { planner.synchronize(); - // Send 'N' to force homing before G29 (internal only) - if (axes_should_home() || parser.seen_test('N')) gcode.home_all_axes(); - TERN_(HAS_MULTI_HOTEND, if (active_extruder != 0) tool_change(0, true)); + #if ALL(DWIN_LCD_PROUI, ZHOME_BEFORE_LEVELING) + save_ubl_active_state_and_disable(); + gcode.process_subcommands_now(F("G28Z")); + restore_ubl_active_state(false); // ...without telling ExtUI "done" + #else + // Send 'N' to force homing before G29 (internal only) + if (axes_should_home() || parser.seen_test('N')) gcode.home_all_axes(); + #endif + probe.use_probing_tool(); + + #ifdef EVENT_GCODE_BEFORE_G29 + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Before G29 G-code: ", EVENT_GCODE_BEFORE_G29); + gcode.process_subcommands_now(F(EVENT_GCODE_BEFORE_G29)); + #endif // Position bed horizontally and Z probe vertically. - #if defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \ - || defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \ - || defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W) + #if HAS_SAFE_BED_LEVELING xyze_pos_t safe_position = current_position; #ifdef SAFE_BED_LEVELING_START_X safe_position.x = SAFE_BED_LEVELING_START_X; @@ -351,16 +365,16 @@ void unified_bed_leveling::G29() { #endif do_blocking_move_to(safe_position); - #endif + #endif // HAS_SAFE_BED_LEVELING } // Invalidate one or more nearby mesh points, possibly all. if (parser.seen('I')) { - uint8_t count = parser.has_value() ? parser.value_byte() : 1; + grid_count_t count = parser.has_value() ? parser.value_ushort() : 1; bool invalidate_all = count >= GRID_MAX_POINTS; if (!invalidate_all) { while (count--) { - if ((count & 0x0F) == 0x0F) idle(); + if ((count & 0x0F) == 0x0F) marlin.idle(); const mesh_index_pair closest = find_closest_mesh_point_of_type(REAL, param.XY_pos); // No more REAL mesh points to invalidate? Assume the user meant // to invalidate the ENTIRE mesh, which can't be done with @@ -382,7 +396,7 @@ void unified_bed_leveling::G29() { if (parser.seen('Q')) { const int16_t test_pattern = parser.has_value() ? parser.value_int() : -99; if (!WITHIN(test_pattern, TERN0(UBL_DEVEL_DEBUGGING, -1), 2)) { - SERIAL_ECHOLNPGM("?Invalid (Q) test pattern. (" TERN(UBL_DEVEL_DEBUGGING, "-1", "0") " to 2)\n"); + SERIAL_ECHOLN(F("?Invalid "), F("(Q) test pattern. (" TERN(UBL_DEVEL_DEBUGGING, "-1", "0") " to 2)\n")); return; } SERIAL_ECHOLNPGM("Applying test pattern.\n"); @@ -401,13 +415,13 @@ void unified_bed_leveling::G29() { break; case 1: - LOOP_L_N(x, GRID_MAX_POINTS_X) { // Create a diagonal line several Mesh cells thick that is raised + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; ++x) { // Create a diagonal line several Mesh cells thick that is raised const uint8_t x2 = x + (x < (GRID_MAX_POINTS_Y) - 1 ? 1 : -1); z_values[x][x] += 9.999f; z_values[x][x2] += 9.999f; // We want the altered line several mesh points thick #if ENABLED(EXTENSIBLE_UI) ExtUI::onMeshUpdate(x, x, z_values[x][x]); - ExtUI::onMeshUpdate(x, (x2), z_values[x][x2]); + ExtUI::onMeshUpdate(x, x2, z_values[x][x2]); #endif } break; @@ -428,12 +442,12 @@ void unified_bed_leveling::G29() { if (parser.seen_test('J')) { save_ubl_active_state_and_disable(); tilt_mesh_based_on_probed_grid(param.J_grid_size == 0); // Zero size does 3-Point - restore_ubl_active_state_and_leave(); + restore_ubl_active_state(); #if ENABLED(UBL_G29_J_RECENTER) do_blocking_move_to_xy(0.5f * ((MESH_MIN_X) + (MESH_MAX_X)), 0.5f * ((MESH_MIN_Y) + (MESH_MAX_Y))); #endif report_current_position(); - probe_deployed = true; + SET_PROBE_DEPLOYED(true); } #endif // HAS_BED_PROBE @@ -463,16 +477,12 @@ void unified_bed_leveling::G29() { invalidate(); SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh."); } - if (param.V_verbosity > 1) { - SERIAL_ECHOPGM("Probing around (", param.XY_pos.x); - SERIAL_CHAR(','); - SERIAL_DECIMAL(param.XY_pos.y); - SERIAL_ECHOLNPGM(").\n"); - } + if (param.V_verbosity > 1) + SERIAL_ECHOLN(F("Probing around ("), param.XY_pos.x, C(','), param.XY_pos.y, F(").\n")); probe_entire_mesh(param.XY_pos, parser.seen_test('T'), parser.seen_test('E'), parser.seen_test('U')); report_current_position(); - probe_deployed = true; + SET_PROBE_DEPLOYED(true); } break; #endif // HAS_BED_PROBE @@ -510,7 +520,7 @@ void unified_bed_leveling::G29() { SERIAL_ECHOLNPGM("?Error in Business Card measurement."); return; } - probe_deployed = true; + SET_PROBE_DEPLOYED(true); } if (!position_is_reachable(param.XY_pos)) { @@ -600,7 +610,7 @@ void unified_bed_leveling::G29() { case 5: adjust_mesh_to_mean(param.C_seen, param.C_constant); break; - case 6: shift_mesh_height(); break; + case 6: shift_mesh_height(param.C_constant); break; } } @@ -622,7 +632,6 @@ void unified_bed_leveling::G29() { #endif // UBL_DEVEL_DEBUGGING - // // Load a Mesh from the EEPROM // @@ -638,7 +647,7 @@ void unified_bed_leveling::G29() { } if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLN(F("?Invalid "), F("storage slot.\n?Use 0 to "), a - 1); return; } @@ -666,7 +675,7 @@ void unified_bed_leveling::G29() { } if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLN(F("?Invalid "), F("storage slot.\n?Use 0 to "), a - 1); goto LEAVE; } @@ -688,17 +697,15 @@ void unified_bed_leveling::G29() { ui.release(); #endif - #ifdef Z_PROBE_END_SCRIPT - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Probe End Script: ", Z_PROBE_END_SCRIPT); + #ifdef EVENT_GCODE_AFTER_G29 + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("After G29 G-code: ", EVENT_GCODE_AFTER_G29); if (probe_deployed) { planner.synchronize(); - gcode.process_subcommands_now(F(Z_PROBE_END_SCRIPT)); + gcode.process_subcommands_now(F(EVENT_GCODE_AFTER_G29)); } - #else - UNUSED(probe_deployed); #endif - TERN_(HAS_MULTI_HOTEND, if (old_tool_index != 0) tool_change(old_tool_index)); + probe.use_probing_tool(false); return; } @@ -707,7 +714,7 @@ void unified_bed_leveling::G29() { * G29 P5 C : Adjust Mesh To Mean (and subtract the given offset). * Find the mean average and shift the mesh to center on that value. */ -void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t offset) { +void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const float offset) { float sum = 0; uint8_t n = 0; GRID_LOOP(x, y) @@ -727,10 +734,10 @@ void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t o sum_of_diff_squared += sq(z_values[x][y] - mean); SERIAL_ECHOLNPGM("# of samples: ", n); - SERIAL_ECHOLNPAIR_F("Mean Mesh Height: ", mean, 6); + SERIAL_ECHOLNPGM("Mean Mesh Height: ", p_float_t(mean, 6)); const float sigma = SQRT(sum_of_diff_squared / (n + 1)); - SERIAL_ECHOLNPAIR_F("Standard Deviation: ", sigma, 6); + SERIAL_ECHOLNPGM("Standard Deviation: ", p_float_t(sigma, 6)); if (cflag) GRID_LOOP(x, y) @@ -743,10 +750,10 @@ void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t o /** * G29 P6 C : Shift Mesh Height by a uniform constant. */ -void unified_bed_leveling::shift_mesh_height() { +void unified_bed_leveling::shift_mesh_height(const float zoffs) { GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { - z_values[x][y] += param.C_constant; + z_values[x][y] += zoffs; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } } @@ -762,19 +769,19 @@ 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; + grid_count_t count = GRID_MAX_POINTS; mesh_index_pair best; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::G29_START)); do { if (do_ubl_mesh_map) display_map(param.T_map_type); - const uint8_t point_num = (GRID_MAX_POINTS - count) + 1; + const grid_count_t point_num = (GRID_MAX_POINTS - count) + 1; SERIAL_ECHOLNPGM("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); + TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); #if HAS_MARLINUI_MENU if (ui.button_pressed()) { @@ -784,22 +791,22 @@ void unified_bed_leveling::shift_mesh_height() { ui.quick_feedback(); ui.release(); probe.stow(); // Release UI before stow to allow for PAUSE_BEFORE_DEPLOY_STOW - TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); - return restore_ubl_active_state_and_leave(); + return restore_ubl_active_state(); } #endif - best = do_furthest + #ifndef HUGE_VALF + #define HUGE_VALF __FLT_MAX__ + #endif + + best = do_furthest // Points with valid data or HUGE_VALF are skipped ? find_furthest_invalid_mesh_point() : find_closest_mesh_point_of_type(INVALID, nearby, true); if (best.pos.x >= 0) { // mesh point found and is reachable by probe TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::G29_POINT_START)); - const float measured_z = probe.probe_at_point( - best.meshpos(), - stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity - ); - z_values[best.pos.x][best.pos.y] = measured_z; + const float measured_z = probe.probe_at_point(best.meshpos(), stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); + z_values[best.pos.x][best.pos.y] = isnan(measured_z) ? HUGE_VALF : measured_z; // Mark invalid point already probed with HUGE_VALF to omit it in the next loop #if ENABLED(EXTENSIBLE_UI) ExtUI::onMeshUpdate(best.pos, ExtUI::G29_POINT_FINISH); ExtUI::onMeshUpdate(best.pos, measured_z); @@ -809,6 +816,8 @@ void unified_bed_leveling::shift_mesh_height() { } while (best.pos.x >= 0 && --count); + GRID_LOOP(x, y) if (z_values[x][y] == HUGE_VALF) z_values[x][y] = NAN; // Restore NAN for HUGE_VALF marks + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::G29_FINISH)); // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW @@ -818,15 +827,12 @@ void unified_bed_leveling::shift_mesh_height() { probe.move_z_after_probing(); - restore_ubl_active_state_and_leave(); - do_blocking_move_to_xy( constrain(nearby.x - probe.offset_xy.x, MESH_MIN_X, MESH_MAX_X), constrain(nearby.y - probe.offset_xy.y, MESH_MIN_Y, MESH_MAX_Y) ); - TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); - TERN_(DWIN_LCD_PROUI, DWIN_LevelingDone()); + restore_ubl_active_state(); } #endif // HAS_BED_PROBE @@ -849,7 +855,7 @@ void set_message_with_feedback(FSTR_P const fstr) { ui.quick_feedback(false); // Preserve button state for click-and-hold const millis_t nxt = millis() + 1500UL; while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag! - idle(); // idle, of course + marlin.idle(); // idle, of course if (ELAPSED(millis(), nxt)) { // After 1.5 seconds ui.quick_feedback(); if (func) (*func)(); @@ -862,10 +868,10 @@ void set_message_with_feedback(FSTR_P const fstr) { return false; } - void unified_bed_leveling::move_z_with_encoder(const_float_t multiplier) { + void unified_bed_leveling::move_z_with_encoder(const float multiplier) { ui.wait_for_release(); while (!ui.button_pressed()) { - idle(); + marlin.idle(); gcode.reset_stepper_timeout(); // Keep steppers powered if (encoder_diff) { do_blocking_move_to_z(current_position.z + float(encoder_diff) * multiplier); @@ -887,8 +893,32 @@ void set_message_with_feedback(FSTR_P const fstr) { ui.capture(); save_ubl_active_state_and_disable(); // Disable bed level correction for probing - do_blocking_move_to(0.5f * (MESH_MAX_X - (MESH_MIN_X)), 0.5f * (MESH_MAX_Y - (MESH_MIN_Y)), MANUAL_PROBE_START_Z); - //, _MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]) * 0.5f); + do_blocking_move_to( + xyz_pos_t({ + 0.5f * ((MESH_MAX_X) - (MESH_MIN_X)), + 0.5f * ((MESH_MAX_Y) - (MESH_MIN_Y)), + MANUAL_PROBE_START_Z + #ifdef SAFE_BED_LEVELING_START_I + , SAFE_BED_LEVELING_START_I + #endif + #ifdef SAFE_BED_LEVELING_START_J + , SAFE_BED_LEVELING_START_J + #endif + #ifdef SAFE_BED_LEVELING_START_K + , SAFE_BED_LEVELING_START_K + #endif + #ifdef SAFE_BED_LEVELING_START_U + , SAFE_BED_LEVELING_START_U + #endif + #ifdef SAFE_BED_LEVELING_START_V + , SAFE_BED_LEVELING_START_V + #endif + #ifdef SAFE_BED_LEVELING_START_W + , SAFE_BED_LEVELING_START_W + #endif + }) + //, _MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]) * 0.5f + ); planner.synchronize(); SERIAL_ECHOPGM("Place shim under nozzle"); @@ -897,24 +927,21 @@ void set_message_with_feedback(FSTR_P const fstr) { echo_and_take_a_measurement(); const float z1 = measure_point_with_encoder(); - do_blocking_move_to_z(current_position.z + SIZE_OF_LITTLE_RAISE); - planner.synchronize(); + do_z_clearance_by(SIZE_OF_LITTLE_RAISE); SERIAL_ECHOPGM("Remove shim"); LCD_MESSAGE(MSG_UBL_BC_REMOVE); echo_and_take_a_measurement(); const float z2 = measure_point_with_encoder(); - do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES); + do_z_clearance_by(Z_CLEARANCE_BETWEEN_PROBES); const float thickness = ABS(z1 - z2); - if (param.V_verbosity > 1) { - SERIAL_ECHOPAIR_F("Business Card is ", thickness, 4); - SERIAL_ECHOLNPGM("mm thick."); - } + if (param.V_verbosity > 1) + SERIAL_ECHOLNPGM("Business Card is ", p_float_t(thickness, 4), "mm thick."); - restore_ubl_active_state_and_leave(); + restore_ubl_active_state(); return thickness; } @@ -924,7 +951,7 @@ void set_message_with_feedback(FSTR_P const fstr) { * Move to INVALID points and * NOTE: Blocks the G-code queue and captures Marlin UI during use. */ - void unified_bed_leveling::manually_probe_remaining_mesh(const xy_pos_t &pos, const_float_t z_clearance, const_float_t thick, const bool do_ubl_mesh_map) { + void unified_bed_leveling::manually_probe_remaining_mesh(const xy_pos_t &pos, const float z_clearance, const float thick, const bool do_ubl_mesh_map) { ui.capture(); TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); @@ -969,7 +996,7 @@ void set_message_with_feedback(FSTR_P const fstr) { if (_click_and_hold([]{ SERIAL_ECHOLNPGM("\nMesh only partially populated."); do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE); - })) return restore_ubl_active_state_and_leave(); + })) return restore_ubl_active_state(); // Store the Z position minus the shim height z_values[lpos.x][lpos.y] = current_position.z - thick; @@ -978,16 +1005,14 @@ void set_message_with_feedback(FSTR_P const fstr) { TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, z_values[lpos.x][lpos.y])); if (param.V_verbosity > 2) - SERIAL_ECHOLNPAIR_F("Mesh Point Measured at: ", z_values[lpos.x][lpos.y], 6); + SERIAL_ECHOLNPGM("Mesh Point Measured at: ", p_float_t(z_values[lpos.x][lpos.y], 6)); SERIAL_FLUSH(); // Prevent host M105 buffer overrun. } while (location.valid()); if (do_ubl_mesh_map) display_map(param.T_map_type); // show user where we're probing - restore_ubl_active_state_and_leave(); + restore_ubl_active_state(); do_blocking_move_to_xy_z(pos, Z_CLEARANCE_DEPLOY_PROBE); - - TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); } /** @@ -1016,9 +1041,9 @@ void set_message_with_feedback(FSTR_P const fstr) { save_ubl_active_state_and_disable(); LCD_MESSAGE(MSG_UBL_FINE_TUNE_MESH); - ui.capture(); // Take over control of the LCD encoder + ui.capture(); // Take over control of the LCD encoder - do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance + do_blocking_move_to_xy_z(pos, Z_TWEEN_SAFE_CLEARANCE); // Move to the given XY with probe clearance MeshFlags done_flags{0}; const xy_int8_t &lpos = location.pos; @@ -1035,7 +1060,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 = { get_mesh_x(lpos.x), get_mesh_y(lpos.y), Z_CLEARANCE_BETWEEN_PROBES }; + const xyz_pos_t raw = { get_mesh_x(lpos.x), get_mesh_y(lpos.y), Z_TWEEN_SAFE_CLEARANCE }; if (!position_is_reachable(raw)) break; // SHOULD NOT OCCUR (find_closest_mesh_point_of_type only returns reachable) @@ -1045,7 +1070,7 @@ void set_message_with_feedback(FSTR_P const fstr) { KEEPALIVE_STATE(PAUSED_FOR_USER); - if (do_ubl_mesh_map) display_map(param.T_map_type); // Display the current point + if (do_ubl_mesh_map) display_map(param.T_map_type); // Display the current point #if IS_TFTGLCD_PANEL ui.ubl_plot(lpos.x, lpos.y); // update plot screen @@ -1062,7 +1087,7 @@ void set_message_with_feedback(FSTR_P const fstr) { SET_SOFT_ENDSTOP_LOOSE(true); do { - idle_no_sleep(); + marlin.idle_no_sleep(); new_z = ui.ubl_mesh_value(); TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited SERIAL_FLUSH(); // Prevent host M105 buffer overrun. @@ -1075,7 +1100,7 @@ void set_message_with_feedback(FSTR_P const fstr) { // Button held down? Abort editing if (_click_and_hold([]{ ui.return_to_status(); - do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); + do_z_clearance(Z_TWEEN_SAFE_CLEARANCE); set_message_with_feedback(GET_TEXT_F(MSG_EDITING_STOPPED)); })) break; @@ -1093,9 +1118,9 @@ void set_message_with_feedback(FSTR_P const fstr) { } while (lpos.x >= 0 && --param.R_repetition > 0); if (do_ubl_mesh_map) display_map(param.T_map_type); - restore_ubl_active_state_and_leave(); + restore_ubl_active_state(); - do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); + do_blocking_move_to_xy_z(pos, Z_TWEEN_SAFE_CLEARANCE); LCD_MESSAGE(MSG_UBL_DONE_EDITING_MESH); SERIAL_ECHOLNPGM("Done Editing Mesh"); @@ -1120,7 +1145,7 @@ bool unified_bed_leveling::G29_parse_parameters() { param.R_repetition = 0; if (parser.seen('R')) { - param.R_repetition = parser.has_value() ? parser.value_byte() : GRID_MAX_POINTS; + param.R_repetition = parser.has_value() ? parser.value_ushort() : GRID_MAX_POINTS; NOMORE(param.R_repetition, GRID_MAX_POINTS); if (param.R_repetition < 1) { SERIAL_ECHOLNPGM("?(R)epetition count invalid (1+).\n"); @@ -1135,16 +1160,16 @@ bool unified_bed_leveling::G29_parse_parameters() { } if (parser.seen('P')) { - const uint8_t pv = parser.value_byte(); + const uint8_t pval = parser.value_byte(); #if !HAS_BED_PROBE - if (pv == 1) { + if (pval == 1) { SERIAL_ECHOLNPGM("G29 P1 requires a probe.\n"); err_flag = true; } else #endif { - param.P_phase = pv; + param.P_phase = pval; if (!WITHIN(param.P_phase, 0, 6)) { SERIAL_ECHOLNPGM("?(P)hase value invalid (0-6).\n"); err_flag = true; @@ -1156,7 +1181,7 @@ bool unified_bed_leveling::G29_parse_parameters() { #if HAS_BED_PROBE param.J_grid_size = parser.value_byte(); if (param.J_grid_size && !WITHIN(param.J_grid_size, 2, 9)) { - SERIAL_ECHOLNPGM("?Invalid grid size (J) specified (2-9).\n"); + SERIAL_ECHOLN(F("?Invalid "), F("grid size (J) specified (2-9).\n")); err_flag = true; } #else @@ -1245,17 +1270,20 @@ void unified_bed_leveling::save_ubl_active_state_and_disable() { set_bed_leveling_enabled(false); } -void unified_bed_leveling::restore_ubl_active_state_and_leave() { +void unified_bed_leveling::restore_ubl_active_state(const bool is_done/*=true*/) { TERN_(HAS_MARLINUI_MENU, ui.release()); #if ENABLED(UBL_DEVEL_DEBUGGING) if (--ubl_state_recursion_chk) { - SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times."); + SERIAL_ECHOLNPGM("restore_ubl_active_state() called too many times."); set_message_with_feedback(GET_TEXT_F(MSG_UBL_RESTORE_ERROR)); return; } #endif set_bed_leveling_enabled(ubl_state_at_invocation); - TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); + + if (is_done) { + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); + } } mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { @@ -1430,7 +1458,7 @@ void unified_bed_leveling::smart_fill_mesh() { info3 PROGMEM = { (GRID_MAX_POINTS_X) - 1, 0, 0, GRID_MAX_POINTS_Y, true }; // Right side of the mesh looking left static const smart_fill_info * const info[] PROGMEM = { &info0, &info1, &info2, &info3 }; - LOOP_L_N(i, COUNT(info)) { + for (uint8_t i = 0; i < COUNT(info); ++i) { const smart_fill_info *f = (smart_fill_info*)pgm_read_ptr(&info[i]); const int8_t sx = pgm_read_byte(&f->sx), sy = pgm_read_byte(&f->sy), ex = pgm_read_byte(&f->ex), ey = pgm_read_byte(&f->ey); @@ -1456,81 +1484,42 @@ void unified_bed_leveling::smart_fill_mesh() { #include "../../../libs/vector_3.h" void unified_bed_leveling::tilt_mesh_based_on_probed_grid(const bool do_3_pt_leveling) { - const float x_min = probe.min_x(), x_max = probe.max_x(), - y_min = probe.min_y(), y_max = probe.max_y(), - dx = (x_max - x_min) / (param.J_grid_size - 1), - dy = (y_max - y_min) / (param.J_grid_size - 1); - - xy_float_t points[3]; - probe.get_three_points(points); float measured_z; bool abort_flag = false; - #ifdef VALIDATE_MESH_TILT - float z1, z2, z3; // Needed for algorithm validation below - #endif - struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); if (do_3_pt_leveling) { - SERIAL_ECHOLNPGM("Tilting mesh (1/3)"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); + xy_float_t points[3]; + probe.get_three_points(points); - measured_z = probe.probe_at_point(points[0], PROBE_PT_RAISE, param.V_verbosity); - if (isnan(measured_z)) - abort_flag = true; - else { - measured_z -= get_z_correction(points[0]); - #ifdef VALIDATE_MESH_TILT - z1 = measured_z; - #endif - if (param.V_verbosity > 3) { - serial_spaces(16); - SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); + #if ENABLED(UBL_TILT_ON_MESH_POINTS_3POINT) + mesh_index_pair cpos[3]; + for (uint8_t ix = 0; ix < 3; ++ix) { // Convert points to coordinates of mesh points + cpos[ix] = find_closest_mesh_point_of_type(REAL, points[ix], true); + points[ix] = cpos[ix].meshpos(); } - incremental_LSF(&lsf_results, points[0], measured_z); - } + #endif - if (!abort_flag) { - SERIAL_ECHOLNPGM("Tilting mesh (2/3)"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); + #if ENABLED(VALIDATE_MESH_TILT) + float gotz[3]; // Used for algorithm validation below + #endif - measured_z = probe.probe_at_point(points[1], PROBE_PT_RAISE, param.V_verbosity); - #ifdef VALIDATE_MESH_TILT - z2 = measured_z; - #endif - if (isnan(measured_z)) - abort_flag = true; - else { - measured_z -= get_z_correction(points[1]); - if (param.V_verbosity > 3) { - serial_spaces(16); - SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); - } - incremental_LSF(&lsf_results, points[1], measured_z); - } - } + for (uint8_t i = 0; i < 3; ++i) { + SERIAL_ECHOLNPGM("Tilting mesh (", i + 1, "/3)"); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_LCD_TILTING_MESH), i + 1)); - if (!abort_flag) { - SERIAL_ECHOLNPGM("Tilting mesh (3/3)"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); + measured_z = probe.probe_at_point(points[i], i < 2 ? PROBE_PT_RAISE : PROBE_PT_LAST_STOW, param.V_verbosity); + if ((abort_flag = isnan(measured_z))) break; - measured_z = probe.probe_at_point(points[2], PROBE_PT_LAST_STOW, param.V_verbosity); - #ifdef VALIDATE_MESH_TILT - z3 = measured_z; - #endif - if (isnan(measured_z)) - abort_flag = true; - else { - measured_z -= get_z_correction(points[2]); - if (param.V_verbosity > 3) { - serial_spaces(16); - SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); - } - incremental_LSF(&lsf_results, points[2], measured_z); - } + measured_z -= TERN(UBL_TILT_ON_MESH_POINTS_3POINT, z_values[cpos[i].pos.x][cpos[i].pos.y], get_z_correction(points[i])); + TERN_(VALIDATE_MESH_TILT, gotz[i] = measured_z); + + if (param.V_verbosity > 3) { SERIAL_ECHO_SP(16); SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); } + + incremental_LSF(&lsf_results, points[i], measured_z); } probe.stow(); @@ -1543,75 +1532,94 @@ void unified_bed_leveling::smart_fill_mesh() { } else { // !do_3_pt_leveling + #ifndef G29J_MESH_TILT_MARGIN + #define G29J_MESH_TILT_MARGIN 0 + #endif + const float x_min = _MAX((X_MIN_POS) + (G29J_MESH_TILT_MARGIN), MESH_MIN_X, probe.min_x()), + x_max = _MIN((X_MAX_POS) - (G29J_MESH_TILT_MARGIN), MESH_MAX_X, probe.max_x()), + y_min = _MAX((Y_MIN_POS) + (G29J_MESH_TILT_MARGIN), MESH_MIN_Y, probe.min_y()), + y_max = _MIN((Y_MAX_POS) - (G29J_MESH_TILT_MARGIN), MESH_MAX_Y, probe.max_y()), + dx = (x_max - x_min) / (param.J_grid_size - 1), + dy = (y_max - y_min) / (param.J_grid_size - 1); + bool zig_zag = false; const uint16_t total_points = sq(param.J_grid_size); uint16_t point_num = 1; - xy_pos_t rpos; - LOOP_L_N(ix, param.J_grid_size) { + for (uint8_t ix = 0; ix < param.J_grid_size; ++ix) { + xy_pos_t rpos; rpos.x = x_min + ix * dx; - LOOP_L_N(iy, param.J_grid_size) { + for (uint8_t iy = 0; iy < param.J_grid_size; ++iy) { rpos.y = y_min + dy * (zig_zag ? param.J_grid_size - 1 - iy : iy); - if (!abort_flag) { - SERIAL_ECHOLNPGM("Tilting mesh point ", point_num, "/", total_points, "\n"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); - - measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling - - abort_flag = isnan(measured_z); - + #if ENABLED(UBL_TILT_ON_MESH_POINTS) #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - const xy_pos_t lpos = rpos.asLogical(); - DEBUG_CHAR('('); - DEBUG_ECHO_F(rpos.x, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(rpos.y, 7); - DEBUG_ECHOPAIR_F(") logical: (", lpos.x, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(lpos.y, 7); - DEBUG_ECHOPAIR_F(") measured: ", measured_z, 7); - DEBUG_ECHOPAIR_F(" correction: ", get_z_correction(rpos), 7); - } + xy_pos_t oldRpos; + if (DEBUGGING(LEVELING)) oldRpos = rpos; #endif + mesh_index_pair cpos; + rpos -= probe.offset; + cpos = find_closest_mesh_point_of_type(REAL, rpos, true); + rpos = cpos.meshpos(); + #endif - measured_z -= get_z_correction(rpos) /* + probe.offset.z */ ; + SERIAL_ECHOLNPGM("Tilting mesh point ", point_num, "/", total_points, "\n"); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_F(" final >>>---> ", measured_z, 7); + measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling - if (param.V_verbosity > 3) { - serial_spaces(16); - SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); + if ((abort_flag = isnan(measured_z))) break; + + const float zcorr = TERN(UBL_TILT_ON_MESH_POINTS, z_values[cpos.pos.x][cpos.pos.y], get_z_correction(rpos)); + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + #if ENABLED(UBL_TILT_ON_MESH_POINTS) + const xy_pos_t oldLpos = oldRpos.asLogical(); + DEBUG_ECHO(F("Calculated point: ("), p_float_t(oldRpos.x, 7), C(','), p_float_t(oldRpos.y, 7), + F(") logical: ("), p_float_t(oldLpos.x, 7), C(','), p_float_t(oldLpos.y, 7), + F(")\nSelected mesh point: ") + ); + #endif + const xy_pos_t lpos = rpos.asLogical(); + DEBUG_ECHO( C('('), p_float_t(rpos.x, 7), C(','), p_float_t(rpos.y, 7), + F(") logical: ("), p_float_t(lpos.x, 7), C(','), p_float_t(lpos.y, 7), + F(") measured: "), p_float_t(measured_z, 7), + F(" correction: "), p_float_t(zcorr, 7) + ); } - incremental_LSF(&lsf_results, rpos, measured_z); + #endif + + measured_z -= zcorr; + + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(" final >>>---> ", p_float_t(measured_z, 7)); + + if (param.V_verbosity > 3) { + SERIAL_ECHO_SP(16); + SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); } + incremental_LSF(&lsf_results, rpos, measured_z); point_num++; } - zig_zag ^= true; + if (abort_flag) break; + FLIP(zig_zag); } } probe.stow(); probe.move_z_after_probing(); if (abort_flag || finish_incremental_LSF(&lsf_results)) { - SERIAL_ECHOPGM("Could not complete LSF!"); + SERIAL_ECHOLNPGM("Could not complete LSF!"); return; } vector_3 normal = vector_3(lsf_results.A, lsf_results.B, 1).get_normal(); - if (param.V_verbosity > 2) { - SERIAL_ECHOPAIR_F("bed plane normal = [", normal.x, 7); - SERIAL_CHAR(','); - SERIAL_ECHO_F(normal.y, 7); - SERIAL_CHAR(','); - SERIAL_ECHO_F(normal.z, 7); - SERIAL_ECHOLNPGM("]"); - } + if (param.V_verbosity > 2) + SERIAL_ECHOLN(F("bed plane normal = ["), p_float_t(normal.x, 7), C(','), p_float_t(normal.y, 7), C(','), p_float_t(normal.z, 7), C(']')); matrix_3x3 rotation = matrix_3x3::create_look_at(vector_3(lsf_results.A, lsf_results.B, 1)); @@ -1619,24 +1627,14 @@ void unified_bed_leveling::smart_fill_mesh() { 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); - DEBUG_CHAR(','); - DEBUG_ECHO_F(my, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(mz, 7); - DEBUG_ECHOPGM("] ---> "); + DEBUG_ECHOLN(F("before rotation = ["), p_float_t(mx, 7), C(','), p_float_t(my, 7), C(','), p_float_t(mz, 7), F("] ---> ")); 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_ECHOLN(F("after rotation = ["), p_float_t(mx, 7), C(','), p_float_t(my, 7), C(','), p_float_t(mz, 7), F("] ---> ")); DEBUG_DELAY(20); } @@ -1646,17 +1644,9 @@ void unified_bed_leveling::smart_fill_mesh() { if (DEBUGGING(LEVELING)) { rotation.debug(F("rotation matrix:\n")); - DEBUG_ECHOPAIR_F("LSF Results A=", lsf_results.A, 7); - DEBUG_ECHOPAIR_F(" B=", lsf_results.B, 7); - DEBUG_ECHOLNPAIR_F(" D=", lsf_results.D, 7); + DEBUG_ECHOLN(F("LSF Results A="), p_float_t(lsf_results.A, 7), F(" B="), p_float_t(lsf_results.B, 7), F(" D="), p_float_t(lsf_results.D, 7)); DEBUG_DELAY(55); - - DEBUG_ECHOPAIR_F("bed plane normal = [", normal.x, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(normal.y, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(normal.z, 7); - DEBUG_ECHOLNPGM("]"); + DEBUG_ECHOLN(F("bed plane normal = ["), p_float_t(normal.x, 7), C(','), p_float_t(normal.y, 7), C(','), p_float_t(normal.z, 7), C(']')); DEBUG_EOL(); /** @@ -1667,25 +1657,24 @@ void unified_bed_leveling::smart_fill_mesh() { * The Z error between the probed point locations and the get_z_correction() * numbers for those locations should be 0. */ - #ifdef VALIDATE_MESH_TILT + #if ENABLED(VALIDATE_MESH_TILT) auto d_from = []{ DEBUG_ECHOPGM("D from "); }; - auto normed = [&](const xy_pos_t &pos, const_float_t zadd) { + auto normed = [&](const xy_pos_t &pos, const float zadd) { return normal.x * pos.x + normal.y * pos.y + zadd; }; - auto debug_pt = [](FSTR_P const pre, const xy_pos_t &pos, const_float_t zadd) { - d_from(); SERIAL_ECHOF(pre); - DEBUG_ECHO_F(normed(pos, zadd), 6); - DEBUG_ECHOLNPAIR_F(" Z error = ", zadd - get_z_correction(pos), 6); + auto debug_pt = [](const int num, const xy_pos_t &pos, const float zadd) { + d_from(); + DEBUG_ECHOLN(F("Point "), num, C(':'), p_float_t(normed(pos, zadd), 6), F(" Z error = "), p_float_t(zadd - get_z_correction(pos), 6)); }; - debug_pt(F("1st point: "), probe_pt[0], normal.z * z1); - debug_pt(F("2nd point: "), probe_pt[1], normal.z * z2); - debug_pt(F("3rd point: "), probe_pt[2], normal.z * z3); - d_from(); DEBUG_ECHOPGM("safe home with Z="); - DEBUG_ECHOLNPAIR_F("0 : ", normed(safe_homing_xy, 0), 6); - d_from(); DEBUG_ECHOPGM("safe home with Z="); - DEBUG_ECHOLNPAIR_F("mesh value ", normed(safe_homing_xy, get_z_correction(safe_homing_xy)), 6); - DEBUG_ECHOPGM(" Z error = (", Z_SAFE_HOMING_X_POINT, ",", Z_SAFE_HOMING_Y_POINT); - DEBUG_ECHOLNPAIR_F(") = ", get_z_correction(safe_homing_xy), 6); + debug_pt(1, probe_pt[0], normal.z * gotz[0]); + debug_pt(2, probe_pt[1], normal.z * gotz[1]); + debug_pt(3, probe_pt[2], normal.z * gotz[2]); + #if ENABLED(Z_SAFE_HOMING) + constexpr xy_float_t safe_xy = { Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT }; + d_from(); DEBUG_ECHOLN(F("safe home with Z="), F("0 : "), p_float_t(normed(safe_xy, 0), 6)); + d_from(); DEBUG_ECHOLN(F("safe home with Z="), F("mesh value "), p_float_t(normed(safe_xy, get_z_correction(safe_xy)), 6)); + DEBUG_ECHO(F(" Z error = ("), Z_SAFE_HOMING_X_POINT, C(','), Z_SAFE_HOMING_Y_POINT, F(") = "), p_float_t(get_z_correction(safe_xy), 6)); + #endif #endif } // DEBUGGING(LEVELING) @@ -1694,7 +1683,7 @@ void unified_bed_leveling::smart_fill_mesh() { #endif // HAS_BED_PROBE #if ENABLED(UBL_G29_P31) - void unified_bed_leveling::smart_fill_wlsf(const_float_t weight_factor) { + void unified_bed_leveling::smart_fill_wlsf(const float weight_factor) { // For each undefined mesh point, compute a distance-weighted least squares fit // from all the originally populated mesh points, weighted toward the point @@ -1712,17 +1701,17 @@ void unified_bed_leveling::smart_fill_mesh() { GRID_LOOP(jx, jy) if (!isnan(z_values[jx][jy])) SBI(bitmap[jx], jy); xy_pos_t ppos; - LOOP_L_N(ix, GRID_MAX_POINTS_X) { + for (uint8_t ix = 0; ix < GRID_MAX_POINTS_X; ++ix) { ppos.x = get_mesh_x(ix); - LOOP_L_N(iy, GRID_MAX_POINTS_Y) { + for (uint8_t iy = 0; iy < GRID_MAX_POINTS_Y; ++iy) { ppos.y = get_mesh_y(iy); if (isnan(z_values[ix][iy])) { // undefined mesh point at (ppos.x,ppos.y), compute weighted LSF from original valid mesh points. incremental_LSF_reset(&lsf_results); xy_pos_t rpos; - LOOP_L_N(jx, GRID_MAX_POINTS_X) { + for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; ++jx) { rpos.x = get_mesh_x(jx); - LOOP_L_N(jy, GRID_MAX_POINTS_Y) { + for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; ++jy) { if (TEST(bitmap[jx], jy)) { rpos.y = get_mesh_y(jy); const float rz = z_values[jx][jy], @@ -1732,18 +1721,18 @@ void unified_bed_leveling::smart_fill_mesh() { } } if (finish_incremental_LSF(&lsf_results)) { - SERIAL_ECHOLNPGM("Insufficient data"); + SERIAL_ECHOLNPGM(" Insufficient data"); return; } const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y; z_values[ix][iy] = ez; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy])); - idle(); // housekeeping + marlin.idle(); // housekeeping } } } - SERIAL_ECHOLNPGM("done"); + SERIAL_ECHOLNPGM(" done."); } #endif // UBL_G29_P31 @@ -1756,20 +1745,19 @@ void unified_bed_leveling::smart_fill_mesh() { report_state(); if (storage_slot == -1) - SERIAL_ECHOPGM("No Mesh Loaded."); + SERIAL_ECHOLNPGM("No Mesh Loaded."); else - SERIAL_ECHOPGM("Mesh ", storage_slot, " Loaded."); - SERIAL_EOL(); + SERIAL_ECHOLNPGM("Mesh ", storage_slot, " Loaded."); serial_delay(50); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - SERIAL_ECHOLNPAIR_F("Fade Height M420 Z", planner.z_fade_height, 4); + SERIAL_ECHOLN(F("Fade Height M420 Z"), p_float_t(planner.z_fade_height, 4)); #endif adjust_mesh_to_mean(param.C_seen, param.C_constant); #if HAS_BED_PROBE - SERIAL_ECHOLNPAIR_F("Probe Offset M851 Z", probe.offset.z, 7); + SERIAL_ECHOLNPGM("Probe Offset M851 Z", p_float_t(probe.offset.z, 7)); #endif SERIAL_ECHOLNPGM("MESH_MIN_X " STRINGIFY(MESH_MIN_X) "=", MESH_MIN_X); serial_delay(50); @@ -1782,45 +1770,41 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHOLNPGM("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50); SERIAL_ECHOPGM("X-Axis Mesh Points at: "); - LOOP_L_N(i, GRID_MAX_POINTS_X) { - SERIAL_ECHO_F(LOGICAL_X_POSITION(get_mesh_x(i)), 3); - SERIAL_ECHOPGM(" "); + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { + SERIAL_ECHO(p_float_t(LOGICAL_X_POSITION(get_mesh_x(i)), 3), F(" ")); serial_delay(25); } SERIAL_EOL(); SERIAL_ECHOPGM("Y-Axis Mesh Points at: "); - LOOP_L_N(i, GRID_MAX_POINTS_Y) { - SERIAL_ECHO_F(LOGICAL_Y_POSITION(get_mesh_y(i)), 3); - SERIAL_ECHOPGM(" "); + for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; ++i) { + SERIAL_ECHO(p_float_t(LOGICAL_Y_POSITION(get_mesh_y(i)), 3), F(" ")); serial_delay(25); } SERIAL_EOL(); #if HAS_KILL - SERIAL_ECHOLNPGM("Kill pin on :", KILL_PIN, " state:", kill_state()); + SERIAL_ECHOLNPGM("Kill pin on :", KILL_PIN, " state:", marlin.kill_state()); #endif SERIAL_EOL(); serial_delay(50); - #if ENABLED(UBL_DEVEL_DEBUGGING) - SERIAL_ECHOLNPGM("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk); - serial_delay(50); + SERIAL_ECHOLNPGM("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk); + serial_delay(50); - SERIAL_ECHOLNPGM("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); - serial_delay(50); + SERIAL_ECHOLNPGM("Meshes go from ", _hex_word(settings.meshes_start_index()), " to ", _hex_word(settings.meshes_end_index())); + serial_delay(50); - SERIAL_ECHOLNPGM("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL(); - SERIAL_ECHOLNPGM("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL(); - serial_delay(25); + SERIAL_ECHOLNPGM("sizeof(unified_bed_leveling) : ", sizeof(unified_bed_leveling)); + SERIAL_ECHOLNPGM("z_value[][] size: ", sizeof(z_values)); + serial_delay(25); - SERIAL_ECHOLNPGM("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); - serial_delay(50); + SERIAL_ECHOLNPGM("EEPROM free for UBL: ", _hex_word(settings.meshes_end_index() - settings.meshes_start_index())); + serial_delay(50); - SERIAL_ECHOLNPGM("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n"); - serial_delay(25); - #endif // UBL_DEVEL_DEBUGGING + SERIAL_ECHOLNPGM("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n"); + serial_delay(25); if (!sanity_check()) { echo_name(); @@ -1838,11 +1822,12 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHO_MSG("EEPROM Dump:"); persistentStore.access_start(); for (uint16_t i = 0; i < persistentStore.capacity(); i += 16) { - if (!(i & 0x3)) idle(); + if (!(i & 0x3)) marlin.idle(); print_hex_word(i); SERIAL_ECHOPGM(": "); for (uint16_t j = 0; j < 16; j++) { - persistentStore.read_data(i + j, &cccc, sizeof(uint8_t)); + int pos = i + j; + persistentStore.read_data(pos, &cccc, sizeof(uint8_t)); print_hex_byte(cccc); SERIAL_CHAR(' '); } @@ -1865,7 +1850,7 @@ void unified_bed_leveling::smart_fill_mesh() { } if (!parser.has_value() || !WITHIN(parser.value_int(), 0, a - 1)) { - SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLN(F("?Invalid "), F("storage slot.\n?Use 0 to "), a - 1); return; } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 18110c67fa..b6b9ec4368 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -32,7 +32,6 @@ #include "../../../module/delta.h" #endif -#include "../../../MarlinCore.h" #include //#define DEBUG_UBL_MOTION @@ -47,7 +46,7 @@ // 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) { + void unified_bed_leveling::line_to_destination_cartesian(const feedRate_t scaled_fr_mm_s, const uint8_t extruder) { /** * Much of the nozzle movement will be within the same cell. So we will do as little computation * as possible to determine if this is the case. If this move is within the same cell, we will @@ -61,7 +60,7 @@ const xyze_pos_t &start = current_position, &end = destination; #endif - const xy_int8_t istart = cell_indexes(start), iend = cell_indexes(end); + const xy_uint8_t istart = cell_indexes(start), iend = cell_indexes(end); // A move within the same cell needs no splitting if (istart == iend) { @@ -108,7 +107,7 @@ const xy_float_t dist = end - start; const xy_bool_t neg { dist.x < 0, dist.y < 0 }; - const xy_int8_t ineg { int8_t(neg.x), int8_t(neg.y) }; + const xy_uint8_t ineg { uint8_t(neg.x), uint8_t(neg.y) }; const xy_float_t sign { neg.x ? -1.0f : 1.0f, neg.y ? -1.0f : 1.0f }; const xy_int8_t iadd { int8_t(iend.x == istart.x ? 0 : sign.x), int8_t(iend.y == istart.y ? 0 : sign.y) }; @@ -131,7 +130,7 @@ const bool inf_normalized_flag = isinf(e_normalized_dist); #endif - xy_int8_t icell = istart; + xy_uint8_t icell = istart; const float ratio = dist.y / dist.x, // Allow divide by zero c = start.y - ratio * start.x; @@ -252,7 +251,7 @@ * Generic case of a line crossing both X and Y Mesh lines. */ - xy_int8_t cnt = (istart - iend).ABS(); + xy_uint8_t cnt = istart.diff(iend); icell += ineg; @@ -334,16 +333,14 @@ #else // UBL_SEGMENTED #if IS_SCARA - #define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm - #elif ENABLED(DELTA) - #define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND) - #elif ENABLED(POLARGRAPH) - #define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND) + #define SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm + #elif IS_KINEMATIC + #define SEGMENT_MIN_LENGTH 0.10 // (mm) Still subject to DEFAULT_SEGMENTS_PER_SECOND #else // CARTESIAN #ifdef LEVELED_SEGMENT_LENGTH - #define DELTA_SEGMENT_MIN_LENGTH LEVELED_SEGMENT_LENGTH + #define SEGMENT_MIN_LENGTH LEVELED_SEGMENT_LENGTH #else - #define DELTA_SEGMENT_MIN_LENGTH 1.00 // mm (similar to G2/G3 arc segmentation) + #define SEGMENT_MIN_LENGTH 1.00 // (mm) Similar to G2/G3 arc segmentation #endif #endif @@ -353,7 +350,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 @@ -361,23 +358,23 @@ const xyze_pos_t total = destination - current_position; const float cart_xy_mm_2 = HYPOT2(total.x, total.y), - cart_xy_mm = SQRT(cart_xy_mm_2); // Total XY distance + cart_xy_mm = SQRT(cart_xy_mm_2); // Total XY distance #if IS_KINEMATIC - const float seconds = cart_xy_mm / scaled_fr_mm_s; // Duration of XY move at requested rate - uint16_t segments = LROUND(segments_per_second * seconds), // Preferred number of segments for distance @ feedrate - seglimit = LROUND(cart_xy_mm * RECIPROCAL(DELTA_SEGMENT_MIN_LENGTH)); // Number of segments at minimum segment length - NOMORE(segments, seglimit); // Limit to minimum segment length (fewer segments) + const float seconds = cart_xy_mm / scaled_fr_mm_s; // Duration of XY move at requested rate + uint16_t segments = LROUND(segments_per_second * seconds), // Preferred number of segments for distance @ feedrate + seglimit = LROUND(cart_xy_mm * RECIPROCAL(SEGMENT_MIN_LENGTH)); // Number of segments at minimum segment length + NOMORE(segments, seglimit); // Limit to minimum segment length (fewer segments) #else - uint16_t segments = LROUND(cart_xy_mm * RECIPROCAL(DELTA_SEGMENT_MIN_LENGTH)); // Cartesian fixed segment length + uint16_t segments = LROUND(cart_xy_mm * RECIPROCAL(SEGMENT_MIN_LENGTH)); // Cartesian fixed segment length #endif - NOLESS(segments, 1U); // Must have at least one segment - const float inv_segments = 1.0f / segments; // Reciprocal to save calculation + NOLESS(segments, 1U); // Must have at least one segment + const float inv_segments = 1.0f / segments; // Reciprocal to save calculation // Add hints to help optimize the move - PlannerHints hints(SQRT(cart_xy_mm_2 + sq(total.z)) * inv_segments); // Length of each segment - #if ENABLED(SCARA_FEEDRATE_SCALING) + PlannerHints hints(SQRT(cart_xy_mm_2 + sq(total.z)) * inv_segments); // Length of each segment + #if ENABLED(FEEDRATE_SCALING) hints.inv_duration = scaled_fr_mm_s / hints.millimeters; #endif @@ -423,10 +420,12 @@ LIMIT(icell.x, 0, GRID_MAX_CELLS_X); LIMIT(icell.y, 0, GRID_MAX_CELLS_Y); - float z_x0y0 = z_values[icell.x ][icell.y ], // z at lower left corner - z_x1y0 = z_values[icell.x+1][icell.y ], // z at upper left corner - z_x0y1 = z_values[icell.x ][icell.y+1], // z at lower right corner - z_x1y1 = z_values[icell.x+1][icell.y+1]; // z at upper right corner + const int8_t ncellx = _MIN(icell.x+1, GRID_MAX_CELLS_X), + ncelly = _MIN(icell.y+1, GRID_MAX_CELLS_Y); + float z_x0y0 = z_values[icell.x][icell.y], // z at lower left corner + z_x1y0 = z_values[ncellx ][icell.y], // z at upper left corner + z_x0y1 = z_values[icell.x][ncelly ], // z at lower right corner + z_x1y1 = z_values[ncellx ][ncelly ]; // z at upper right corner if (isnan(z_x0y0)) z_x0y0 = 0; // ideally activating planner.leveling_active (G29 A) if (isnan(z_x1y0)) z_x1y0 = 0; // should refuse if any invalid mesh points diff --git a/Marlin/src/feature/binary_stream.h b/Marlin/src/feature/binary_stream.h index 417e39c745..304fdae300 100644 --- a/Marlin/src/feature/binary_stream.h +++ b/Marlin/src/feature/binary_stream.h @@ -134,21 +134,21 @@ private: public: static void idle() { - // If a transfer is interrupted and a file is left open, abort it after TIMEOUT ms + // If a transfer is interrupted and a file is left open, abort it after 'idle_period' ms const millis_t ms = millis(); if (transfer_active && ELAPSED(ms, idle_timeout)) { - idle_timeout = ms + IDLE_PERIOD; + idle_timeout = ms + idle_period; if (ELAPSED(ms, transfer_timeout)) transfer_abort(); } } static void process(uint8_t packet_type, char *buffer, const uint16_t length) { - transfer_timeout = millis() + TIMEOUT; + transfer_timeout = millis() + timeout; switch (static_cast(packet_type)) { case FileTransfer::QUERY: - SERIAL_ECHOPGM("PFT:version:", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH); + SERIAL_ECHO(F("PFT:version:"), version_major, C('.'), version_minor, C('.'), version_patch); #if ENABLED(BINARY_STREAM_COMPRESSION) - SERIAL_ECHOLNPGM(":compression:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS); + SERIAL_ECHOLN(F(":compression:heatshrink,"), HEATSHRINK_STATIC_WINDOW_BITS, C(','), HEATSHRINK_STATIC_LOOKAHEAD_BITS); #else SERIAL_ECHOLNPGM(":compression:none"); #endif @@ -194,7 +194,7 @@ public: } } - static const uint16_t VERSION_MAJOR = 0, VERSION_MINOR = 1, VERSION_PATCH = 0, TIMEOUT = 10000, IDLE_PERIOD = 1000; + static const uint16_t version_major = 0, version_minor = 1, version_patch = 0, timeout = 10000, idle_period = 1000; }; class BinaryStream { @@ -209,7 +209,7 @@ public: struct Packet { // 10 byte protocol overhead, ascii with checksum and line number has a minimum of 7 increasing with line union Header { - static constexpr uint16_t HEADER_TOKEN = 0xB5AD; + static constexpr uint16_t header_token = 0xB5AD; struct [[gnu::packed]] { uint16_t token; // packet start token uint8_t sync; // stream sync, resend id and packet loss detection @@ -245,7 +245,7 @@ public: bytes_received = 0; checksum = 0; header_checksum = 0; - timeout = millis() + PACKET_MAX_WAIT; + timeout = millis() + packet_max_wait; buffer = nullptr; } } packet{}; @@ -272,16 +272,16 @@ public: } if (!bs_serial_data_available(card.transfer_port_index)) return false; data = bs_read_serial(card.transfer_port_index); - packet.timeout = millis() + PACKET_MAX_WAIT; + packet.timeout = millis() + packet_max_wait; return true; } template void receive(char (&buffer)[buffer_size]) { uint8_t data = 0; - millis_t transfer_window = millis() + RX_TIMESLICE; + millis_t transfer_window = millis() + rx_timeslice; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA PORT_REDIRECT(SERIAL_PORTMASK(card.transfer_port_index)); #endif @@ -299,7 +299,7 @@ public: case StreamState::PACKET_WAIT: if (!stream_read(data)) { idle(); return; } // no active packet so don't wait packet.header.data[1] = data; - if (packet.header.token == packet.header.HEADER_TOKEN) { + if (packet.header.token == packet.header.header_token) { packet.bytes_received = 2; stream_state = StreamState::PACKET_HEADER; } @@ -322,7 +322,7 @@ public: if (packet.header.checksum == packet.header_checksum) { // The SYNC control packet is a special case in that it doesn't require the stream sync to be correct if (static_cast(packet.header.protocol()) == Protocol::CONTROL && static_cast(packet.header.type()) == ProtocolControl::SYNC) { - SERIAL_ECHOLNPGM("ss", sync, ",", buffer_size, ",", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH); + SERIAL_ECHOLN(F("ss"), sync, C(','), buffer_size, C(','), version_major, C('.'), version_minor, C('.'), version_patch); stream_state = StreamState::PACKET_RESET; break; } @@ -398,7 +398,7 @@ public: stream_state = StreamState::PACKET_RESET; break; case StreamState::PACKET_RESEND: - if (packet_retries < MAX_RETRIES || MAX_RETRIES == 0) { + if (packet_retries < max_retries || max_retries == 0) { packet_retries++; stream_state = StreamState::PACKET_RESET; SERIAL_ECHO_MSG("Resend request ", packet_retries); @@ -446,7 +446,7 @@ public: SDFileTransferProtocol::idle(); } - static const uint16_t PACKET_MAX_WAIT = 500, RX_TIMESLICE = 20, MAX_RETRIES = 0, VERSION_MAJOR = 0, VERSION_MINOR = 1, VERSION_PATCH = 0; + static const uint16_t packet_max_wait = 500, rx_timeslice = 20, max_retries = 0, version_major = 0, version_minor = 1, version_patch = 0; uint8_t packet_retries, sync; uint16_t buffer_next_index; uint32_t bytes_received; diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index 10d3131aed..85b69d66c4 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -29,7 +29,7 @@ BLTouch bltouch; bool BLTouch::od_5v_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain -#ifdef BLTOUCH_HS_MODE +#if HAS_BLTOUCH_HS_MODE bool BLTouch::high_speed_mode; // Initialized by settings.load, 0 = Low Speed; 1 = High Speed #else constexpr bool BLTouch::high_speed_mode; @@ -38,15 +38,18 @@ bool BLTouch::od_5v_mode; // Initialized by settings.load, 0 = Open Drai #include "../module/servo.h" #include "../module/probe.h" -void stop(); - #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" bool BLTouch::command(const BLTCommand cmd, const millis_t &ms) { - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("BLTouch Command :", cmd); - servo[Z_PROBE_SERVO_NR].move(cmd); - safe_delay(_MAX(ms, (uint32_t)BLTOUCH_DELAY)); // BLTOUCH_DELAY is also the *minimum* delay + const BLTCommand current = servo[Z_PROBE_SERVO_NR].read(); + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("BLTouch from ", current, " to ", cmd); + // If the new command is the same, skip it (and the delay). + // The previous write should've already delayed to detect the alarm. + if (cmd != current) { + servo[Z_PROBE_SERVO_NR].move(cmd); + safe_delay(_MAX(ms, uint32_t(BLTOUCH_DELAY))); // BLTOUCH_DELAY is also the *minimum* delay + } return triggered(); } @@ -68,15 +71,9 @@ void BLTouch::init(const bool set_voltage/*=false*/) { #else - #ifdef DEBUG_OUT - if (DEBUGGING(LEVELING)) { - PGMSTR(mode0, "OD"); - PGMSTR(mode1, "5V"); - DEBUG_ECHOPGM("BLTouch Mode: "); - DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); - DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); - } - #endif + if (DEBUGGING(LEVELING)) + DEBUG_ECHOLN( F("BLTouch Mode: "), bltouch.od_5v_mode ? F("5V") : F("OD"), + F(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")")); const bool should_set = od_5v_mode != ENABLED(BLTOUCH_SET_5V_MODE); diff --git a/Marlin/src/feature/bltouch.h b/Marlin/src/feature/bltouch.h index fa857bb96a..1371ec9f46 100644 --- a/Marlin/src/feature/bltouch.h +++ b/Marlin/src/feature/bltouch.h @@ -26,6 +26,7 @@ // BLTouch commands are sent as servo angles typedef unsigned char BLTCommand; +#define DEPLOY_ALARM true #define STOW_ALARM true #define BLTOUCH_DEPLOY 10 #define BLTOUCH_STOW 90 @@ -70,13 +71,13 @@ public: static void init(const bool set_voltage=false); static bool od_5v_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain - #ifdef BLTOUCH_HS_MODE + #if HAS_BLTOUCH_HS_MODE static bool high_speed_mode; // Initialized by settings.load, 0 = Low Speed; 1 = High Speed #else static constexpr bool high_speed_mode = false; #endif - static float z_extra_clearance() { return high_speed_mode ? 7 : 0; } + static float z_extra_clearance() { return TERN0(HAS_BLTOUCH_HS_MODE, high_speed_mode ? BLTOUCH_HS_EXTRA_CLEARANCE : 0); } // DEPLOY and STOW are wrapped for error handling - these are used by homing and by probing static bool deploy() { return deploy_proc(); } @@ -104,7 +105,7 @@ public: static bool triggered(); private: - static bool _deploy_query_alarm() { return command(BLTOUCH_DEPLOY, BLTOUCH_DEPLOY_DELAY); } + static bool _deploy_query_alarm() { return command(BLTOUCH_DEPLOY, BLTOUCH_DEPLOY_DELAY) == DEPLOY_ALARM; } static bool _stow_query_alarm() { return command(BLTOUCH_STOW, BLTOUCH_STOW_DELAY) == STOW_ALARM; } static void clear(); diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp index bffd2bb720..c17c9988e4 100644 --- a/Marlin/src/feature/cancel_object.cpp +++ b/Marlin/src/feature/cancel_object.cpp @@ -30,23 +30,20 @@ CancelObject cancelable; -int8_t CancelObject::object_count, // = 0 - CancelObject::active_object = -1; -uint32_t CancelObject::canceled; // = 0x0000 -bool CancelObject::skipping; // = false +cancel_state_t CancelObject::state; void CancelObject::set_active_object(const int8_t obj) { - active_object = obj; + state.active_object = obj; if (WITHIN(obj, 0, 31)) { - if (obj >= object_count) object_count = obj + 1; - skipping = TEST(canceled, obj); + if (obj >= state.object_count) state.object_count = obj + 1; + state.skipping = TEST(state.canceled, obj); } else - skipping = false; + state.skipping = false; - #if BOTH(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) - if (active_object >= 0) - ui.status_printf(0, F(S_FMT " %i"), GET_TEXT(MSG_PRINTING_OBJECT), int(active_object)); + #if ALL(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) + if (state.active_object >= 0) + ui.set_status(MString<30>(GET_TEXT_F(MSG_PRINTING_OBJECT), ' ', state.active_object)); else ui.reset_status(); #endif @@ -54,29 +51,29 @@ void CancelObject::set_active_object(const int8_t obj) { void CancelObject::cancel_object(const int8_t obj) { if (WITHIN(obj, 0, 31)) { - SBI(canceled, obj); - if (obj == active_object) skipping = true; + SBI(state.canceled, obj); + if (obj == state.active_object) state.skipping = true; } } void CancelObject::uncancel_object(const int8_t obj) { if (WITHIN(obj, 0, 31)) { - CBI(canceled, obj); - if (obj == active_object) skipping = false; + CBI(state.canceled, obj); + if (obj == state.active_object) state.skipping = false; } } void CancelObject::report() { - if (active_object >= 0) - SERIAL_ECHO_MSG("Active Object: ", active_object); + if (state.active_object >= 0) + SERIAL_ECHO_MSG("Active Object: ", state.active_object); - if (canceled) { - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Canceled:"); - for (int i = 0; i < object_count; i++) - if (TEST(canceled, i)) { SERIAL_CHAR(' '); SERIAL_ECHO(i); } - SERIAL_EOL(); - } + if (state.canceled == 0x0000) return; + + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("Canceled:"); + for (int i = 0; i < state.object_count; i++) + if (TEST(state.canceled, i)) SERIAL_ECHO(C(' '), i); + SERIAL_EOL(); } #endif // CANCEL_OBJECTS diff --git a/Marlin/src/feature/cancel_object.h b/Marlin/src/feature/cancel_object.h index 62548a3719..7f04612d13 100644 --- a/Marlin/src/feature/cancel_object.h +++ b/Marlin/src/feature/cancel_object.h @@ -23,19 +23,23 @@ #include +typedef struct CancelState { + bool skipping = false; + int8_t object_count = 0, active_object = 0; + uint32_t canceled = 0x0000; +} cancel_state_t; + class CancelObject { public: - static bool skipping; - static int8_t object_count, active_object; - static uint32_t canceled; - static void set_active_object(const int8_t obj); + static cancel_state_t state; + static void set_active_object(const int8_t obj=state.active_object); static void cancel_object(const int8_t obj); static void uncancel_object(const int8_t obj); static void report(); - static bool is_canceled(const int8_t obj) { return TEST(canceled, obj); } + static bool is_canceled(const int8_t obj) { return TEST(state.canceled, obj); } static void clear_active_object() { set_active_object(-1); } - static void cancel_active_object() { cancel_object(active_object); } - static void reset() { canceled = 0x0000; object_count = 0; clear_active_object(); } + static void cancel_active_object() { cancel_object(state.active_object); } + static void reset() { state.canceled = 0x0000; state.object_count = 0; clear_active_object(); } }; extern CancelObject cancelable; diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index eb580a6d62..95221111b2 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -40,7 +40,7 @@ bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; #if CASE_LIGHT_IS_COLOR_LED constexpr uint8_t init_case_light[] = CASE_LIGHT_DEFAULT_COLOR; - LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2] OPTARG(HAS_WHITE_LED, init_case_light[3]) }; + LED1Color_t CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2] OPTARG(HAS_WHITE_LED, init_case_light[3]) }; #endif void CaseLight::update(const bool sflag) { @@ -67,13 +67,13 @@ void CaseLight::update(const bool sflag) { #if ENABLED(CASE_LIGHT_USE_NEOPIXEL) if (on) // Use current color of (NeoPixel) leds and new brightness level - leds.set_color(LEDColor(leds.color.r, leds.color.g, leds.color.b OPTARG(HAS_WHITE_LED, leds.color.w) OPTARG(NEOPIXEL_LED, n10ct))); + leds.set_color(LED1Color_t(leds.color.r, leds.color.g, leds.color.b OPTARG(HAS_WHITE_LED, leds.color.w) OPTARG(NEOPIXEL_LED, n10ct))); else // Switch off leds leds.set_off(); #else // Use CaseLight color (CASE_LIGHT_DEFAULT_COLOR) and new brightness level - leds.set_color(LEDColor(color.r, color.g, color.b OPTARG(HAS_WHITE_LED, color.w) OPTARG(NEOPIXEL_LED, n10ct))); + leds.set_color(LED1Color_t(color.r, color.g, color.b OPTARG(HAS_WHITE_LED, color.w) OPTARG(NEOPIXEL_LED, n10ct))); #endif #else // !CASE_LIGHT_IS_COLOR_LED diff --git a/Marlin/src/feature/caselight.h b/Marlin/src/feature/caselight.h index 17e1222acb..28466cecaa 100644 --- a/Marlin/src/feature/caselight.h +++ b/Marlin/src/feature/caselight.h @@ -24,13 +24,13 @@ #include "../inc/MarlinConfig.h" #if CASE_LIGHT_IS_COLOR_LED - #include "leds/leds.h" // for LEDColor + #include "leds/leds.h" // for LED1Color_t #endif class CaseLight { public: static bool on; - #if ENABLED(CASELIGHT_USES_BRIGHTNESS) + #if CASELIGHT_USES_BRIGHTNESS static uint8_t brightness; #endif @@ -50,7 +50,7 @@ public: #if ENABLED(CASE_LIGHT_IS_COLOR_LED) private: - static LEDColor color; + static LED1Color_t color; #endif }; diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index f42bf52ae4..0636402136 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -38,8 +38,36 @@ uint8_t ControllerFan::speed; const controllerFan_settings_t &ControllerFan::settings = controllerFan_defaults; #endif +#if ENABLED(FAN_SOFT_PWM) + uint8_t ControllerFan::soft_pwm_speed; +#endif + void ControllerFan::setup() { SET_OUTPUT(CONTROLLER_FAN_PIN); + #if PIN_EXISTS(CONTROLLER_FAN2) + SET_OUTPUT(CONTROLLER_FAN2_PIN); + #endif + #if PIN_EXISTS(CONTROLLER_FAN3) + SET_OUTPUT(CONTROLLER_FAN3_PIN); + #endif + #if PIN_EXISTS(CONTROLLER_FAN4) + SET_OUTPUT(CONTROLLER_FAN4_PIN); + #endif + #if PIN_EXISTS(CONTROLLER_FAN5) + SET_OUTPUT(CONTROLLER_FAN5_PIN); + #endif + #if PIN_EXISTS(CONTROLLER_FAN6) + SET_OUTPUT(CONTROLLER_FAN6_PIN); + #endif + #if PIN_EXISTS(CONTROLLER_FAN7) + SET_OUTPUT(CONTROLLER_FAN7_PIN); + #endif + #if PIN_EXISTS(CONTROLLER_FAN8) + SET_OUTPUT(CONTROLLER_FAN8_PIN); + #endif + #if PIN_EXISTS(CONTROLLER_FAN9) + SET_OUTPUT(CONTROLLER_FAN9_PIN); + #endif init(); } @@ -48,37 +76,91 @@ void ControllerFan::set_fan_speed(const uint8_t s) { } void ControllerFan::update() { - static millis_t lastMotorOn = 0, // Last time a motor was turned on - nextMotorCheck = 0; // Last time the state was checked + static millis_t lastComponentOn = 0, // Last time a stepper, heater, etc. was turned on + nextFanCheck = 0; // Last time the state was checked const millis_t ms = millis(); - if (ELAPSED(ms, nextMotorCheck)) { - nextMotorCheck = ms + 2500UL; // Not a time critical function, so only check every 2.5s + if (ELAPSED(ms, nextFanCheck)) { + nextFanCheck = ms + 2500UL; // Not a time critical function, so only check every 2.5s - // If any triggers for the controller fan are true... - // - At least one stepper driver is enabled - // - The heated bed is enabled - // - TEMP_SENSOR_BOARD is reporting >= CONTROLLER_FAN_MIN_BOARD_TEMP + /** + * If any triggers for the controller fan are true... + * - At least one stepper driver is enabled + * - The heated bed (MOSFET) is enabled + * - TEMP_SENSOR_BOARD is reporting >= CONTROLLER_FAN_MIN_BOARD_TEMP + * - TEMP_SENSOR_SOC is reporting >= CONTROLLER_FAN_MIN_SOC_TEMP + */ const ena_mask_t axis_mask = TERN(CONTROLLER_FAN_USE_Z_ONLY, _BV(Z_AXIS), (ena_mask_t)~TERN0(CONTROLLER_FAN_IGNORE_Z, _BV(Z_AXIS))); if ( (stepper.axis_enabled.bits & axis_mask) - || TERN0(HAS_HEATED_BED, thermalManager.temp_bed.soft_pwm_amount > 0) - || TERN0(HAS_CONTROLLER_FAN_MIN_BOARD_TEMP, thermalManager.wholeDegBoard() >= CONTROLLER_FAN_MIN_BOARD_TEMP) - ) lastMotorOn = ms; //... set time to NOW so the fan will turn on + #if ALL(HAS_HEATED_BED, CONTROLLER_FAN_BED_HEATING) + || thermalManager.temp_bed.soft_pwm_amount > 0 + #endif + #ifdef CONTROLLER_FAN_MIN_BOARD_TEMP + || thermalManager.wholeDegBoard() >= CONTROLLER_FAN_MIN_BOARD_TEMP + #endif + #ifdef CONTROLLER_FAN_MIN_SOC_TEMP + || thermalManager.wholeDegSoc() >= CONTROLLER_FAN_MIN_SOC_TEMP + #endif + ) lastComponentOn = ms; //... set time to NOW so the fan will turn on - // Fan Settings. Set fan > 0: - // - If AutoMode is on and steppers have been enabled for CONTROLLERFAN_IDLE_TIME seconds. - // - If System is on idle and idle fan speed settings is activated. + /** + * Fan Settings. Set fan > 0: + * - If AutoMode is on and hot components have been powered for CONTROLLERFAN_IDLE_TIME seconds. + * - If System is on idle and idle fan speed settings is activated. + */ set_fan_speed( - settings.auto_mode && lastMotorOn && PENDING(ms, lastMotorOn + SEC_TO_MS(settings.duration)) + settings.auto_mode && lastComponentOn && PENDING(ms, lastComponentOn, SEC_TO_MS(settings.duration)) ? settings.active_speed : settings.idle_speed ); - #if ENABLED(FAN_SOFT_PWM) - thermalManager.soft_pwm_controller_speed = speed; - #else - if (PWM_PIN(CONTROLLER_FAN_PIN)) - hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); + speed = CALC_FAN_SPEED(speed); + + #if FAN_KICKSTART_TIME + static millis_t fan_kick_end = 0; + if (speed > FAN_OFF_PWM) { + if (!fan_kick_end) { + fan_kick_end = ms + FAN_KICKSTART_TIME; // May be longer based on slow update interval for controller fn check. Sets minimum + speed = FAN_KICKSTART_POWER; + } + else if (PENDING(ms, fan_kick_end)) + speed = FAN_KICKSTART_POWER; + } else - WRITE(CONTROLLER_FAN_PIN, speed > 0); + fan_kick_end = 0; + #endif + + #define SET_CONTROLLER_FAN(N) do { \ + if (PWM_PIN(CONTROLLER_FAN##N##_PIN)) hal.set_pwm_duty(pin_t(CONTROLLER_FAN##N##_PIN), speed); \ + else WRITE(CONTROLLER_FAN##N##_PIN, speed > 0);\ + } while (0) + + #if ENABLED(FAN_SOFT_PWM) + soft_pwm_speed = speed >> 1; // Controller Fan Soft PWM uses 0-127 as 0-100% so cut the 0-255 range in half. + #else + SET_CONTROLLER_FAN(); + #if PIN_EXISTS(CONTROLLER_FAN2) + SET_CONTROLLER_FAN(2); + #endif + #if PIN_EXISTS(CONTROLLER_FAN3) + SET_CONTROLLER_FAN(3); + #endif + #if PIN_EXISTS(CONTROLLER_FAN4) + SET_CONTROLLER_FAN(4); + #endif + #if PIN_EXISTS(CONTROLLER_FAN5) + SET_CONTROLLER_FAN(5); + #endif + #if PIN_EXISTS(CONTROLLER_FAN6) + SET_CONTROLLER_FAN(6); + #endif + #if PIN_EXISTS(CONTROLLER_FAN7) + SET_CONTROLLER_FAN(7); + #endif + #if PIN_EXISTS(CONTROLLER_FAN8) + SET_CONTROLLER_FAN(8); + #endif + #if PIN_EXISTS(CONTROLLER_FAN9) + SET_CONTROLLER_FAN(9); + #endif #endif } } diff --git a/Marlin/src/feature/controllerfan.h b/Marlin/src/feature/controllerfan.h index 55eb2359b0..68502afa66 100644 --- a/Marlin/src/feature/controllerfan.h +++ b/Marlin/src/feature/controllerfan.h @@ -60,6 +60,9 @@ class ControllerFan { #else static const controllerFan_settings_t &settings; #endif + #if ENABLED(FAN_SOFT_PWM) + static uint8_t soft_pwm_speed; + #endif static bool state() { return speed > 0; } static void init() { reset(); } static void reset() { TERN_(CONTROLLER_FAN_EDITABLE, settings = controllerFan_defaults); } diff --git a/Marlin/src/feature/cooler.cpp b/Marlin/src/feature/cooler.cpp index e0f99777d1..6c45e99226 100644 --- a/Marlin/src/feature/cooler.cpp +++ b/Marlin/src/feature/cooler.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "cooler.h" Cooler cooler; diff --git a/Marlin/src/feature/cooler.h b/Marlin/src/feature/cooler.h index 9891514e23..ef3590c593 100644 --- a/Marlin/src/feature/cooler.h +++ b/Marlin/src/feature/cooler.h @@ -40,7 +40,7 @@ public: static bool enabled; static void enable() { enabled = true; } static void disable() { enabled = false; } - static void toggle() { enabled = !enabled; } + static void toggle() { FLIP(enabled); } static uint8_t mode; // 0 = CO2 Liquid cooling, 1 = Laser Diode TEC Heatsink Cooling static void set_mode(const uint8_t m) { mode = m; } @@ -96,7 +96,7 @@ public: #if ENABLED(FLOWMETER_SAFETY) static bool flowfault; // Flag that the cooler is in a fault state static bool flowsafety_enabled; // Flag to disable the cutter if flow rate is too low - static void flowsafety_toggle() { flowsafety_enabled = !flowsafety_enabled; } + static void flowsafety_toggle() { FLIP(flowsafety_enabled); } static bool check_flow_too_low() { const bool too_low = flowsafety_enabled && flowrate < (FLOWMETER_MIN_LITERS_PER_MINUTE); flowfault = too_low; diff --git a/Marlin/src/feature/dac/dac_dac084s085.cpp b/Marlin/src/feature/dac/dac_dac084s085.cpp index 772bb68de4..1338e5979d 100644 --- a/Marlin/src/feature/dac/dac_dac084s085.cpp +++ b/Marlin/src/feature/dac/dac_dac084s085.cpp @@ -10,7 +10,6 @@ #include "dac_dac084s085.h" -#include "../../MarlinCore.h" #include "../../HAL/shared/Delay.h" dac084s085::dac084s085() { } diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index f5664bc598..65423d3189 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -68,7 +68,7 @@ void StepperDAC::set_current_value(const uint8_t channel, uint16_t val) { } void StepperDAC::set_current_percent(const uint8_t channel, float val) { - set_current_value(channel, _MIN(val, 100.0f) * (DAC_STEPPER_MAX) / 100.0f); + set_current_value(channel, _MIN(val, 100.0f) * (DAC_STEPPER_MAX) * 0.01f); } static float dac_perc(int8_t n) { return mcp4728.getDrvPct(dac_order[n]); } @@ -87,7 +87,7 @@ void StepperDAC::print_values() { LOOP_LOGICAL_AXES(a) { SERIAL_CHAR(' ', IAXIS_CHAR(a), ':'); SERIAL_ECHO(dac_perc(a)); - SERIAL_ECHOPGM_P(PSTR(" ("), dac_amps(AxisEnum(a)), PSTR(")")); + SERIAL_ECHOPGM_P(PSTR(" ("), dac_amps((AxisEnum)a), PSTR(")")); } #if HAS_EXTRUDERS SERIAL_ECHOLNPGM_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index 3f2ecbfcdc..48d7ff492c 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -37,7 +37,7 @@ #ifndef DIGIPOT_A4988_Vrefmax #define DIGIPOT_A4988_Vrefmax 1.666 #endif -#define DIGIPOT_MCP4018_MAX_VALUE 127 +#define DIGIPOT_MCP4018_MAX_VALUE 127 #define DIGIPOT_A4988_Itripmax(Vref) ((Vref) / (8.0 * DIGIPOT_A4988_Rsx)) @@ -89,7 +89,7 @@ void DigipotI2C::set_current(const uint8_t channel, const float current) { } void DigipotI2C::init() { - LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS) pots[i].i2c_init(); + for (uint8_t i = 0; i < DIGIPOT_I2C_NUM_CHANNELS; ++i) pots[i].i2c_init(); // Init currents according to Configuration_adv.h static const float digipot_motor_current[] PROGMEM = @@ -99,7 +99,7 @@ void DigipotI2C::init() { DIGIPOT_I2C_MOTOR_CURRENTS #endif ; - LOOP_L_N(i, COUNT(digipot_motor_current)) + for (uint8_t i = 0; i < COUNT(digipot_motor_current); ++i) set_current(i, pgm_read_float(&digipot_motor_current[i])); } diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index ba5ecdad05..e35b42a28b 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -35,8 +35,8 @@ // Settings for the I2C based DIGIPOT (MCP4451) on Azteeg X3 Pro #if MB(5DPRINT) - #define DIGIPOT_I2C_FACTOR 117.96f - #define DIGIPOT_I2C_MAX_CURRENT 1.736f + #define DIGIPOT_I2C_FACTOR 117.96f + #define DIGIPOT_I2C_MAX_CURRENT 1.736f #elif MB(AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI) #define DIGIPOT_I2C_FACTOR 113.5f #define DIGIPOT_I2C_MAX_CURRENT 2.0f @@ -94,7 +94,7 @@ void DigipotI2C::init() { DIGIPOT_I2C_MOTOR_CURRENTS #endif ; - LOOP_L_N(i, COUNT(digipot_motor_current)) + for (uint8_t i = 0; i < COUNT(digipot_motor_current); ++i) set_current(i, pgm_read_float(&digipot_motor_current[i])); } diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp index 13cf71e076..08cda561b1 100644 --- a/Marlin/src/feature/direct_stepping.cpp +++ b/Marlin/src/feature/direct_stepping.cpp @@ -175,7 +175,7 @@ namespace DirectStepping { template void SerialPageManager::write_responses() { if (fatal_error) { - kill(GET_TEXT_F(MSG_BAD_PAGE)); + marlin.kill(GET_TEXT_F(MSG_BAD_PAGE)); return; } diff --git a/Marlin/src/feature/direct_stepping.h b/Marlin/src/feature/direct_stepping.h index 962310281e..b8a803f811 100644 --- a/Marlin/src/feature/direct_stepping.h +++ b/Marlin/src/feature/direct_stepping.h @@ -80,9 +80,6 @@ namespace DirectStepping { static void set_page_state(const page_idx_t page_idx, const PageState page_state); }; - template struct TypeSelector { typedef T type;} ; - template struct TypeSelector { typedef F type; }; - template struct config_t { static constexpr char CONTROL_CHAR = '!'; @@ -98,8 +95,8 @@ namespace DirectStepping { static constexpr int TOTAL_STEPS = SEGMENT_STEPS * SEGMENTS; static constexpr int PAGE_SIZE = (AXIS_COUNT * BITS_SEGMENT * SEGMENTS) / 8; - typedef typename TypeSelector<(PAGE_SIZE>256), uint16_t, uint8_t>::type write_byte_idx_t; - typedef typename TypeSelector<(PAGE_COUNT>256), uint16_t, uint8_t>::type page_idx_t; + typedef uvalue_t(PAGE_SIZE - 1) write_byte_idx_t; + typedef uvalue_t(PAGE_COUNT - 1) page_idx_t; }; template diff --git a/Marlin/src/feature/e_parser.cpp b/Marlin/src/feature/e_parser.cpp index d98afcfee7..28a903719c 100644 --- a/Marlin/src/feature/e_parser.cpp +++ b/Marlin/src/feature/e_parser.cpp @@ -24,7 +24,7 @@ * e_parser.cpp - Intercept special commands directly in the serial stream */ -#include "../inc/MarlinConfigPre.h" +#include "../inc/MarlinConfig.h" #if ENABLED(EMERGENCY_PARSER) @@ -33,13 +33,207 @@ // Static data members bool EmergencyParser::killed_by_M112, // = false EmergencyParser::quickstop_by_M410, + #if ENABLED(FTM_RESONANCE_TEST) + EmergencyParser::rt_stop_by_M496, // = false + #endif + #if HAS_MEDIA + EmergencyParser::sd_abort_by_M524, + #endif EmergencyParser::enabled; #if ENABLED(HOST_PROMPT_SUPPORT) + #include "host_actions.h" uint8_t EmergencyParser::M876_reason; // = 0 #endif // Global instance EmergencyParser emergency_parser; +#if ENABLED(EP_BABYSTEPPING) + #include "babystep.h" +#endif + +#if ENABLED(REALTIME_REPORTING_COMMANDS) + // From motion.h, which cannot be included here + void report_current_position_moving(); + void quickpause_stepper(); + void quickresume_stepper(); +#endif + +void EmergencyParser::update(EmergencyParser::State &state, const uint8_t c) { + auto uppercase = [](char c) { + return TERN0(GCODE_CASE_INSENSITIVE, WITHIN(c, 'a', 'z')) ? c + 'A' - 'a' : c; + }; + + switch (state) { + case EP_RESET: + switch (uppercase(c)) { + case ' ': case '\n': case '\r': break; + case 'N': state = EP_N; break; + case 'M': state = EP_M; break; + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case 'S': state = EP_S; break; + case 'P': state = EP_P; break; + case 'R': state = EP_R; break; + #endif + #if ENABLED(SOFT_RESET_VIA_SERIAL) + case '^': state = EP_ctrl; break; + case 'K': state = EP_K; break; + #endif + default: state = EP_IGNORE; + } + break; + + case EP_N: + switch (uppercase(c)) { + case '0' ... '9': + case '-': case ' ': break; + case 'M': state = EP_M; break; + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case 'S': state = EP_S; break; + case 'P': state = EP_P; break; + case 'R': state = EP_R; break; + #endif + default: state = EP_IGNORE; + } + break; + + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case EP_S: state = (c == '0') ? EP_S0 : EP_IGNORE; break; + case EP_S0: state = (c == '0') ? EP_S00 : EP_IGNORE; break; + case EP_S00: state = (c == '0') ? EP_GRBL_STATUS : EP_IGNORE; break; + + case EP_R: state = (c == '0') ? EP_R0 : EP_IGNORE; break; + case EP_R0: state = (c == '0') ? EP_R00 : EP_IGNORE; break; + case EP_R00: state = (c == '0') ? EP_GRBL_RESUME : EP_IGNORE; break; + + case EP_P: state = (c == '0') ? EP_P0 : EP_IGNORE; break; + case EP_P0: state = (c == '0') ? EP_P00 : EP_IGNORE; break; + case EP_P00: state = (c == '0') ? EP_GRBL_PAUSE : EP_IGNORE; break; + #endif + + #if ENABLED(SOFT_RESET_VIA_SERIAL) + case EP_ctrl: state = (c == 'X') ? EP_KILL : EP_IGNORE; break; + case EP_K: state = (c == 'I') ? EP_KI : EP_IGNORE; break; + case EP_KI: state = (c == 'L') ? EP_KIL : EP_IGNORE; break; + case EP_KIL: state = (c == 'L') ? EP_KILL : EP_IGNORE; break; + #endif + + case EP_M: + switch (c) { + case ' ': break; + case '1': state = EP_M1; break; + #if ENABLED(EP_BABYSTEPPING) + case '2': state = EP_M2; break; + #endif + case '4': state = EP_M4; break; + #if HAS_MEDIA + case '5': state = EP_M5; break; + #endif + #if ENABLED(HOST_PROMPT_SUPPORT) + case '8': state = EP_M8; break; + #endif + default: state = EP_IGNORE; + } + break; + + case EP_M1: + switch (c) { + case '0': state = EP_M10; break; + case '1': state = EP_M11; break; + default: state = EP_IGNORE; + } + break; + + case EP_M10: state = (c == '8') ? EP_M108 : EP_IGNORE; break; + case EP_M11: state = (c == '2') ? EP_M112 : EP_IGNORE; break; + case EP_M4: + switch (c) { + case '1' :state = EP_M41; break; + #if ENABLED(FTM_RESONANCE_TEST) + case '9': state = EP_M49; break; + #endif + default: state = EP_IGNORE; + } + break; + + case EP_M41: state = (c == '0') ? EP_M410 : EP_IGNORE; break; + + #if ENABLED(FTM_RESONANCE_TEST) + case EP_M49: state = (c == '6') ? EP_M496 : EP_IGNORE; break; + #endif + + #if HAS_MEDIA + case EP_M5: state = (c == '2') ? EP_M52 : EP_IGNORE; break; + case EP_M52: state = (c == '4') ? EP_M524 : EP_IGNORE; break; + #endif + + #if ENABLED(EP_BABYSTEPPING) + case EP_M2: state = (c == '9') ? EP_M29 : EP_IGNORE; break; + case EP_M29: state = (c == '3') ? EP_M293 : (c == '4') ? EP_M294 : EP_IGNORE; break; + #endif + + #if ENABLED(HOST_PROMPT_SUPPORT) + + case EP_M8: state = (c == '7') ? EP_M87 : EP_IGNORE; break; + case EP_M87: state = (c == '6') ? EP_M876 : EP_IGNORE; break; + + case EP_M876: + switch (uppercase(c)) { + case ' ': break; + case 'S': state = EP_M876S; break; + default: state = EP_IGNORE; break; + } + break; + + case EP_M876S: + switch (c) { + case ' ': break; + case '0' ... '9': + state = EP_M876SN; + M876_reason = uint8_t(c - '0'); + break; + } + break; + + #endif + + case EP_IGNORE: + if (ISEOL(c)) state = EP_RESET; + break; + + default: + if (ISEOL(c)) { + if (enabled) switch (state) { + case EP_M108: marlin.end_waiting(); break; + case EP_M112: killed_by_M112 = true; break; + case EP_M410: quickstop_by_M410 = true; break; + #if ENABLED(FTM_RESONANCE_TEST) + case EP_M496: rt_stop_by_M496 = true; break; + #endif + #if ENABLED(EP_BABYSTEPPING) + case EP_M293: babystep.ep_babysteps++; break; + case EP_M294: babystep.ep_babysteps--; break; + #endif + #if HAS_MEDIA + case EP_M524: sd_abort_by_M524 = true; break; + #endif + #if ENABLED(HOST_PROMPT_SUPPORT) + case EP_M876SN: hostui.handle_response(M876_reason); break; + #endif + #if ENABLED(REALTIME_REPORTING_COMMANDS) + case EP_GRBL_STATUS: report_current_position_moving(); break; + case EP_GRBL_PAUSE: quickpause_stepper(); break; + case EP_GRBL_RESUME: quickresume_stepper(); break; + #endif + #if ENABLED(SOFT_RESET_VIA_SERIAL) + case EP_KILL: hal.reboot(); break; + #endif + default: break; + } + state = EP_RESET; + } + } +} + #endif // EMERGENCY_PARSER diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index fda1ba144b..9f74a38116 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -27,29 +27,11 @@ #include "../inc/MarlinConfigPre.h" -#if ENABLED(HOST_PROMPT_SUPPORT) - #include "host_actions.h" -#endif - -// External references -extern bool wait_for_user, wait_for_heatup; - -#if ENABLED(REALTIME_REPORTING_COMMANDS) - // From motion.h, which cannot be included here - void report_current_position_moving(); - void quickpause_stepper(); - void quickresume_stepper(); -#endif - -#if ENABLED(SOFT_RESET_VIA_SERIAL) - void HAL_reboot(); -#endif - class EmergencyParser { public: - // Currently looking for: M108, M112, M410, M876 S[0-9], S000, P000, R000 + // Currently looking for: M108, M112, M410, M524, M876 S[0-9], S000, P000, R000 enum State : uint8_t { EP_RESET, EP_N, @@ -58,6 +40,15 @@ public: EP_M10, EP_M108, EP_M11, EP_M112, EP_M4, EP_M41, EP_M410, + #if HAS_MEDIA + EP_M5, EP_M52, EP_M524, + #endif + #if ENABLED(FTM_RESONANCE_TEST) + EP_M49, EP_M496, + #endif + #if ENABLED(EP_BABYSTEPPING) + EP_M2, EP_M29, EP_M293, EP_M294, + #endif #if ENABLED(HOST_PROMPT_SUPPORT) EP_M8, EP_M87, EP_M876, EP_M876S, EP_M876SN, #endif @@ -76,6 +67,14 @@ public: static bool killed_by_M112; static bool quickstop_by_M410; + #if ENABLED(FTM_RESONANCE_TEST) + static bool rt_stop_by_M496; + #endif + + #if HAS_MEDIA + static bool sd_abort_by_M524; + #endif + #if ENABLED(HOST_PROMPT_SUPPORT) static uint8_t M876_reason; #endif @@ -85,138 +84,9 @@ public: FORCE_INLINE static void enable() { enabled = true; } FORCE_INLINE static void disable() { enabled = false; } - FORCE_INLINE static void update(State &state, const uint8_t c) { - switch (state) { - case EP_RESET: - switch (c) { - case ' ': case '\n': case '\r': break; - case 'N': state = EP_N; break; - case 'M': state = EP_M; break; - #if ENABLED(REALTIME_REPORTING_COMMANDS) - case 'S': state = EP_S; break; - case 'P': state = EP_P; break; - case 'R': state = EP_R; break; - #endif - #if ENABLED(SOFT_RESET_VIA_SERIAL) - case '^': state = EP_ctrl; break; - case 'K': state = EP_K; break; - #endif - default: state = EP_IGNORE; - } - break; + static void update(State &state, const uint8_t c); - case EP_N: - switch (c) { - case '0' ... '9': - case '-': case ' ': break; - case 'M': state = EP_M; break; - #if ENABLED(REALTIME_REPORTING_COMMANDS) - case 'S': state = EP_S; break; - case 'P': state = EP_P; break; - case 'R': state = EP_R; break; - #endif - default: state = EP_IGNORE; - } - break; - - #if ENABLED(REALTIME_REPORTING_COMMANDS) - case EP_S: state = (c == '0') ? EP_S0 : EP_IGNORE; break; - case EP_S0: state = (c == '0') ? EP_S00 : EP_IGNORE; break; - case EP_S00: state = (c == '0') ? EP_GRBL_STATUS : EP_IGNORE; break; - - case EP_R: state = (c == '0') ? EP_R0 : EP_IGNORE; break; - case EP_R0: state = (c == '0') ? EP_R00 : EP_IGNORE; break; - case EP_R00: state = (c == '0') ? EP_GRBL_RESUME : EP_IGNORE; break; - - case EP_P: state = (c == '0') ? EP_P0 : EP_IGNORE; break; - case EP_P0: state = (c == '0') ? EP_P00 : EP_IGNORE; break; - case EP_P00: state = (c == '0') ? EP_GRBL_PAUSE : EP_IGNORE; break; - #endif - - #if ENABLED(SOFT_RESET_VIA_SERIAL) - case EP_ctrl: state = (c == 'X') ? EP_KILL : EP_IGNORE; break; - case EP_K: state = (c == 'I') ? EP_KI : EP_IGNORE; break; - case EP_KI: state = (c == 'L') ? EP_KIL : EP_IGNORE; break; - case EP_KIL: state = (c == 'L') ? EP_KILL : EP_IGNORE; break; - #endif - - case EP_M: - switch (c) { - case ' ': break; - case '1': state = EP_M1; break; - case '4': state = EP_M4; break; - #if ENABLED(HOST_PROMPT_SUPPORT) - case '8': state = EP_M8; break; - #endif - default: state = EP_IGNORE; - } - break; - - case EP_M1: - switch (c) { - case '0': state = EP_M10; break; - case '1': state = EP_M11; break; - default: state = EP_IGNORE; - } - break; - - case EP_M10: state = (c == '8') ? EP_M108 : EP_IGNORE; break; - case EP_M11: state = (c == '2') ? EP_M112 : EP_IGNORE; break; - case EP_M4: state = (c == '1') ? EP_M41 : EP_IGNORE; break; - case EP_M41: state = (c == '0') ? EP_M410 : EP_IGNORE; break; - - #if ENABLED(HOST_PROMPT_SUPPORT) - - case EP_M8: state = (c == '7') ? EP_M87 : EP_IGNORE; break; - case EP_M87: state = (c == '6') ? EP_M876 : EP_IGNORE; break; - - case EP_M876: - switch (c) { - case ' ': break; - case 'S': state = EP_M876S; break; - default: state = EP_IGNORE; break; - } - break; - - case EP_M876S: - switch (c) { - case ' ': break; - case '0' ... '9': - state = EP_M876SN; - M876_reason = uint8_t(c - '0'); - break; - } - break; - - #endif - - case EP_IGNORE: - if (ISEOL(c)) state = EP_RESET; - break; - - default: - if (ISEOL(c)) { - if (enabled) switch (state) { - case EP_M108: wait_for_user = wait_for_heatup = false; break; - case EP_M112: killed_by_M112 = true; break; - case EP_M410: quickstop_by_M410 = true; break; - #if ENABLED(HOST_PROMPT_SUPPORT) - case EP_M876SN: hostui.handle_response(M876_reason); break; - #endif - #if ENABLED(REALTIME_REPORTING_COMMANDS) - case EP_GRBL_STATUS: report_current_position_moving(); break; - case EP_GRBL_PAUSE: quickpause_stepper(); break; - case EP_GRBL_RESUME: quickresume_stepper(); break; - #endif - #if ENABLED(SOFT_RESET_VIA_SERIAL) - case EP_KILL: HAL_reboot(); break; - #endif - default: break; - } - state = EP_RESET; - } - } - } + static bool isEnabled() { return enabled; } private: static bool enabled; diff --git a/Marlin/src/feature/easythreed_ui.cpp b/Marlin/src/feature/easythreed_ui.cpp index b15daffc09..7180c4dbcd 100644 --- a/Marlin/src/feature/easythreed_ui.cpp +++ b/Marlin/src/feature/easythreed_ui.cpp @@ -78,9 +78,9 @@ void EasythreedUI::blinkLED() { prev_blink_interval_ms = blink_interval_ms; blink_start_ms = ms; } - if (PENDING(ms, blink_start_ms + blink_interval_ms)) + if (PENDING(ms, blink_start_ms, blink_interval_ms)) WRITE(EASYTHREED_LED_PIN, LOW); - else if (PENDING(ms, blink_start_ms + 2 * blink_interval_ms)) + else if (PENDING(ms, blink_start_ms, 2 * blink_interval_ms)) WRITE(EASYTHREED_LED_PIN, HIGH); else blink_start_ms = ms; @@ -91,7 +91,7 @@ void EasythreedUI::blinkLED() { // Load/Unload buttons are a 3 position switch with a common center ground. // void EasythreedUI::loadButton() { - if (printingIsActive()) return; + if (marlin.printingIsActive()) return; enum FilamentStatus : uint8_t { FS_IDLE, FS_PRESS, FS_CHECK, FS_PROCEED }; static uint8_t filament_status = FS_IDLE; @@ -107,7 +107,7 @@ void EasythreedUI::loadButton() { break; case FS_PRESS: - if (ELAPSED(millis(), filament_time + BTN_DEBOUNCE_MS)) { // After a short debounce delay... + if (ELAPSED(millis(), filament_time, BTN_DEBOUNCE_MS)) { // After a short debounce delay... if (!READ(BTN_RETRACT) || !READ(BTN_FEED)) { // ...if switch still toggled... thermalManager.setTargetHotend(EXTRUDE_MINTEMP + 10, 0); // Start heating up blink_interval_ms = LED_BLINK_7; // Set the LED to blink fast @@ -131,7 +131,7 @@ void EasythreedUI::loadButton() { break; case FS_PROCEED: { - // Feed or Retract just once. Hard abort all moves and return to idle on swicth release. + // Feed or Retract just once. Hard abort all moves and return to idle on switch release. static bool flag = false; if (READ(BTN_RETRACT) && READ(BTN_FEED)) { // Switch in center position (stop) flag = false; // Restore flag to false @@ -175,50 +175,47 @@ void EasythreedUI::printButton() { break; case KS_PRESS: - if (ELAPSED(ms, key_time + BTN_DEBOUNCE_MS)) // Wait for debounce interval to expire + if (ELAPSED(ms, key_time, BTN_DEBOUNCE_MS)) // Wait for debounce interval to expire key_status = READ(BTN_PRINT) ? KS_IDLE : KS_PROCEED; // Proceed if still pressed break; case KS_PROCEED: if (!READ(BTN_PRINT)) break; // Wait for the button to be released key_status = KS_IDLE; // Ready for the next press - if (PENDING(ms, key_time + 1200 - BTN_DEBOUNCE_MS)) { // Register a press < 1.2 seconds + if (PENDING(ms, key_time, 1200 - BTN_DEBOUNCE_MS)) { // Register a press < 1.2 seconds switch (print_key_flag) { case PF_START: { // The "Print" button starts an SD card print - if (printingIsActive()) break; // Already printing? (find another line that checks for 'is planner doing anything else right now?') + if (marlin.printingIsActive()) break; // Already printing? (find another line that checks for 'is planner doing anything else right now?') blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals print_key_flag = PF_PAUSE; // The "Print" button now pauses the print card.mount(); // Force SD card to mount - now! - if (!card.isMounted) { // Failed to mount? - blink_interval_ms = LED_OFF; // Turn off LED - print_key_flag = PF_START; - return; // Bail out + if (!card.isMounted()) { // Failed to mount? + blink_interval_ms = LED_OFF; // Turn off LED + print_key_flag = PF_START; + return; // Bail out } card.ls(); // List all files to serial output - const uint16_t filecnt = card.countFilesInWorkDir(); // Count printable files in cwd + const int16_t filecnt = card.get_num_items(); // Count printable files in cwd if (filecnt == 0) return; // None are printable? card.selectFileByIndex(filecnt); // Select the last file according to current sort options card.openAndPrintFile(card.filename); // Start printing it - break; - } + } break; case PF_PAUSE: { // Pause printing (not currently firing) - if (!printingIsActive()) break; + if (!marlin.printingIsActive()) break; blink_interval_ms = LED_ON; // Set indicator to steady ON queue.inject(F("M25")); // Queue Pause print_key_flag = PF_RESUME; // The "Print" button now resumes the print - break; - } + } break; case PF_RESUME: { // Resume printing - if (printingIsActive()) break; + if (marlin.printingIsActive()) break; blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals queue.inject(F("M24")); // Queue resume print_key_flag = PF_PAUSE; // The "Print" button now pauses the print - break; - } + } break; } } else { // Register a longer press - if (print_key_flag == PF_START && !printingIsActive()) { // While not printing, this moves Z up 10mm + if (print_key_flag == PF_START && !marlin.printingIsActive()) { // While not printing, this moves Z up 10mm blink_interval_ms = LED_ON; queue.inject(F("G91\nG0 Z10 F600\nG90")); // Raise Z soon after returning to main loop } diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index 092ce0f8b8..7c83053b89 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -27,7 +27,6 @@ //todo: try faster I2C speed; tweak TWI_FREQ (400000L, or faster?); or just TWBR = ((CPU_FREQ / 400000L) - 16) / 2; //todo: consider Marlin-optimized Wire library; i.e. MarlinWire, like MarlinSerial - #include "../inc/MarlinConfig.h" #if ENABLED(I2C_POSITION_ENCODERS) @@ -37,7 +36,7 @@ #include "../module/stepper.h" #include "../gcode/parser.h" -#include "../feature/babystep.h" +#include "babystep.h" #include @@ -49,7 +48,7 @@ void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) { initialized = true; - SERIAL_ECHOLNPGM("Setting up encoder on ", AS_CHAR(AXIS_CHAR(encoderAxis)), " axis, addr = ", address); + SERIAL_ECHOLNPGM("Setting up encoder on ", C(AXIS_CHAR(encoderAxis)), " axis, addr = ", address); position = get_position(); } @@ -67,7 +66,7 @@ void I2CPositionEncoder::update() { /* if (trusted) { //commented out as part of the note below trusted = false; - SERIAL_ECHOLNPGM("Fault detected on ", AS_CHAR(AXIS_CHAR(encoderAxis)), " axis encoder. Disengaging error correction until module is trusted again."); + SERIAL_ECHOLNPGM("Fault detected on ", C(AXIS_CHAR(encoderAxis)), " axis encoder. Disengaging error correction until module is trusted again."); } */ return; @@ -92,7 +91,7 @@ void I2CPositionEncoder::update() { if (millis() - lastErrorTime > I2CPE_TIME_TRUSTED) { trusted = true; - SERIAL_ECHOLNPGM("Untrusted encoder module on ", AS_CHAR(AXIS_CHAR(encoderAxis)), " axis has been fault-free for set duration, reinstating error correction."); + SERIAL_ECHOLNPGM("Untrusted encoder module on ", C(AXIS_CHAR(encoderAxis)), " axis has been fault-free for set duration, reinstating error correction."); //the encoder likely lost its place when the error occurred, so we'll reset and use the printer's //idea of where it the axis is to re-initialize @@ -106,10 +105,7 @@ void I2CPositionEncoder::update() { SERIAL_ECHOLNPGM("Current position is ", pos); SERIAL_ECHOLNPGM("Position in encoder ticks is ", positionInTicks); SERIAL_ECHOLNPGM("New zero-offset of ", zeroOffset); - SERIAL_ECHOPGM("New position reads as ", get_position()); - SERIAL_CHAR('('); - SERIAL_DECIMAL(mm_from_count(get_position())); - SERIAL_ECHOLNPGM(")"); + SERIAL_ECHOLN(F("New position reads as "), get_position(), C('('), mm_from_count(get_position()), C(')')); #endif } #endif @@ -138,7 +134,7 @@ void I2CPositionEncoder::update() { errIdx = (errIdx >= I2CPE_ERR_ARRAY_SIZE - 1) ? 0 : errIdx + 1; err[errIdx] = get_axis_error_steps(false); - LOOP_L_N(i, I2CPE_ERR_ARRAY_SIZE) { + for (uint8_t i = 0; i < I2CPE_ERR_ARRAY_SIZE; ++i) { sum += err[i]; if (i) diffSum += ABS(err[i-1] - err[i]); } @@ -153,7 +149,7 @@ void I2CPositionEncoder::update() { #ifdef I2CPE_ERR_THRESH_ABORT if (ABS(error) > I2CPE_ERR_THRESH_ABORT * planner.settings.axis_steps_per_mm[encoderAxis]) { - //kill(F("Significant Error")); + //marlin.kill(F("Significant Error")); SERIAL_ECHOLNPGM("Axis error over threshold, aborting!", error); safe_delay(5000); } @@ -170,10 +166,9 @@ void I2CPositionEncoder::update() { errPrst[errPrstIdx++] = error; // Error must persist for I2CPE_ERR_PRST_ARRAY_SIZE error cycles. This also serves to improve the average accuracy if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) { float sumP = 0; - LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i]; + for (uint8_t i = 0; i < I2CPE_ERR_PRST_ARRAY_SIZE; ++i) sumP += errPrst[i]; const int32_t errorP = int32_t(sumP * RECIPROCAL(I2CPE_ERR_PRST_ARRAY_SIZE)); - SERIAL_CHAR(AXIS_CHAR(encoderAxis)); - SERIAL_ECHOLNPGM(" : CORRECT ERR ", errorP * planner.mm_per_step[encoderAxis], "mm"); + SERIAL_ECHOLN(C(AXIS_CHAR(encoderAxis)), F(" : CORRECT ERR "), errorP * planner.mm_per_step[encoderAxis], F("mm")); babystep.add_steps(encoderAxis, -LROUND(errorP)); errPrstIdx = 0; } @@ -192,8 +187,7 @@ void I2CPositionEncoder::update() { if (ABS(error) > I2CPE_ERR_CNT_THRESH * planner.settings.axis_steps_per_mm[encoderAxis]) { const millis_t ms = millis(); if (ELAPSED(ms, nextErrorCountTime)) { - SERIAL_CHAR(AXIS_CHAR(encoderAxis)); - SERIAL_ECHOLNPGM(" : LARGE ERR ", error, "; diffSum=", diffSum); + SERIAL_ECHOLN(C(AXIS_CHAR(encoderAxis)), F(" : LARGE ERR "), error, F("; diffSum="), diffSum); errorCount++; nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS; } @@ -212,8 +206,7 @@ void I2CPositionEncoder::set_homed() { homed = trusted = true; #ifdef I2CPE_DEBUG - SERIAL_CHAR(AXIS_CHAR(encoderAxis)); - SERIAL_ECHOLNPGM(" axis encoder homed, offset of ", zeroOffset, " ticks."); + SERIAL_ECHO(C(AXIS_CHAR(encoderAxis)), F(" axis encoder homed, offset of "), zeroOffset, F(" ticks.\n")); #endif } } @@ -223,8 +216,7 @@ void I2CPositionEncoder::set_unhomed() { homed = trusted = false; #ifdef I2CPE_DEBUG - SERIAL_CHAR(AXIS_CHAR(encoderAxis)); - SERIAL_ECHOLNPGM(" axis encoder unhomed."); + SERIAL_ECHO(C(AXIS_CHAR(encoderAxis)), F(" axis encoder unhomed.\n")); #endif } @@ -232,7 +224,7 @@ bool I2CPositionEncoder::passes_test(const bool report) { if (report) { if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. "); SERIAL_CHAR(AXIS_CHAR(encoderAxis)); - serial_ternary(H == I2CPE_MAG_SIG_BAD, F(" axis "), F("magnetic strip "), F("encoder ")); + serial_ternary(F(" axis "), H == I2CPE_MAG_SIG_BAD, F("magnetic strip "), F("encoder ")); switch (H) { case I2CPE_MAG_SIG_GOOD: case I2CPE_MAG_SIG_MID: @@ -251,10 +243,8 @@ float I2CPositionEncoder::get_axis_error_mm(const bool report) { diff = actual - target, error = ABS(diff) > 10000 ? 0 : diff; // Huge error is a bad reading - if (report) { - SERIAL_CHAR(AXIS_CHAR(encoderAxis)); - SERIAL_ECHOLNPGM(" axis target=", target, "mm; actual=", actual, "mm; err=", error, "mm"); - } + if (report) + SERIAL_ECHO(C(AXIS_CHAR(encoderAxis)), F(" axis target="), target, F("mm; actual="), actual, F("mm; err="), error, F("mm\n")); return error; } @@ -286,10 +276,8 @@ int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) { errorPrev = error; - if (report) { - SERIAL_CHAR(AXIS_CHAR(encoderAxis)); - SERIAL_ECHOLNPGM(" axis target=", target, "; actual=", encoderCountInStepperTicksScaled, "; err=", error); - } + if (report) + SERIAL_ECHOLN(C(AXIS_CHAR(encoderAxis)), F(" axis target="), target, F("; actual="), encoderCountInStepperTicksScaled, F("; err="), error); if (suppressOutput) { if (report) SERIAL_ECHOLNPGM("!Discontinuity. Suppressing error."); @@ -404,7 +392,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { planner.synchronize(); - LOOP_L_N(i, iter) { + for (uint8_t i = 0; i < iter; ++i) { TERN_(HAS_EXTRUDERS, startCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); @@ -425,22 +413,22 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { travelledDistance = mm_from_count(ABS(stopCount - startCount)); SERIAL_ECHOLNPGM("Attempted travel: ", travelDistance, "mm"); - SERIAL_ECHOLNPGM(" Actual travel: ", travelledDistance, "mm"); + SERIAL_ECHOLNPGM(" Actual travel: ", travelledDistance, "mm"); - //Calculate new axis steps per unit + // Calculate new axis steps per unit old_steps_mm = planner.settings.axis_steps_per_mm[encoderAxis]; new_steps_mm = (old_steps_mm * travelDistance) / travelledDistance; SERIAL_ECHOLNPGM("Old steps/mm: ", old_steps_mm); SERIAL_ECHOLNPGM("New steps/mm: ", new_steps_mm); - //Save new value + // Save new value planner.settings.axis_steps_per_mm[encoderAxis] = new_steps_mm; if (iter > 1) { total += new_steps_mm; - // swap start and end points so next loop runs from current position + // Swap start and end points so next loop runs from current position const float tempCoord = startCoord[encoderAxis]; startCoord[encoderAxis] = endCoord[encoderAxis]; endCoord[encoderAxis] = tempCoord; @@ -465,7 +453,6 @@ void I2CPositionEncoder::reset() { TERN_(I2CPE_ERR_ROLLING_AVERAGE, ZERO(err)); } - bool I2CPositionEncodersMgr::I2CPE_anyaxis; uint8_t I2CPositionEncodersMgr::I2CPE_addr, I2CPositionEncodersMgr::I2CPE_idx; @@ -652,23 +639,22 @@ void I2CPositionEncodersMgr::init() { void I2CPositionEncodersMgr::report_position(const int8_t idx, const bool units, const bool noOffset) { CHECK_IDX(); - if (units) + if (units) { SERIAL_ECHOLN(noOffset ? encoders[idx].mm_from_count(encoders[idx].get_raw_count()) : encoders[idx].get_position_mm()); - else { - if (noOffset) { - const int32_t raw_count = encoders[idx].get_raw_count(); - SERIAL_CHAR(AXIS_CHAR(encoders[idx).get_axis()], ' '); - - for (uint8_t j = 31; j > 0; j--) - SERIAL_ECHO((bool)(0x00000001 & (raw_count >> j))); - - SERIAL_ECHO((bool)(0x00000001 & raw_count)); - SERIAL_CHAR(' '); - SERIAL_ECHOLN(raw_count); - } - else - SERIAL_ECHOLN(encoders[idx].get_position()); + return; } + + if (noOffset) { + const int32_t raw_count = encoders[idx].get_raw_count(); + SERIAL_CHAR(AXIS_CHAR(encoders[idx].get_axis()), ' '); + + for (uint8_t j = 31; j >= 0; j--) + SERIAL_ECHO(TEST32(raw_count, j)); + + SERIAL_ECHOLN(C(' '), raw_count); + } + else + SERIAL_ECHOLN(encoders[idx].get_position()); } void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const uint8_t newaddr) { @@ -712,7 +698,7 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const // and enable it (it will likely have failed initialization on power-up, before the address change). const int8_t idx = idx_from_addr(newaddr); if (idx >= 0 && !encoders[idx].get_active()) { - SERIAL_CHAR(AXIS_CHAR(encoders[idx).get_axis()]); + SERIAL_CHAR(AXIS_CHAR(encoders[idx].get_axis())); SERIAL_ECHOLNPGM(" axis encoder was not detected on printer startup. Trying again."); encoders[idx].set_active(encoders[idx].passes_test(true)); } @@ -815,7 +801,7 @@ void I2CPositionEncodersMgr::M860() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen_test(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) report_position(idx, hasU, hasO); } } @@ -842,7 +828,7 @@ void I2CPositionEncodersMgr::M861() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) report_status(idx); } } @@ -870,7 +856,7 @@ void I2CPositionEncodersMgr::M862() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) test_axis(idx); } } @@ -901,7 +887,7 @@ void I2CPositionEncodersMgr::M863() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) calibrate_steps_mm(idx, iterations); } } @@ -977,7 +963,7 @@ void I2CPositionEncodersMgr::M865() { if (!I2CPE_addr) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) report_module_firmware(encoders[idx].get_address()); } } @@ -1008,12 +994,12 @@ void I2CPositionEncodersMgr::M866() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) { if (hasR) - reset_error_count(idx, AxisEnum(i)); + reset_error_count(idx, (AxisEnum)i); else - report_error_count(idx, AxisEnum(i)); + report_error_count(idx, (AxisEnum)i); } } } @@ -1046,10 +1032,10 @@ void I2CPositionEncodersMgr::M867() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) { const bool ena = onoff == -1 ? !encoders[I2CPE_idx].get_ec_enabled() : !!onoff; - enable_ec(idx, ena, AxisEnum(i)); + enable_ec(idx, ena, (AxisEnum)i); } } } @@ -1082,7 +1068,7 @@ void I2CPositionEncodersMgr::M868() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) { if (newThreshold != -9999) set_ec_threshold(idx, newThreshold, encoders[idx].get_axis()); @@ -1116,7 +1102,7 @@ void I2CPositionEncodersMgr::M869() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) report_error(idx); } } diff --git a/Marlin/src/feature/encoder_i2c.h b/Marlin/src/feature/encoder_i2c.h index f25fe2ea6b..e8485a6b75 100644 --- a/Marlin/src/feature/encoder_i2c.h +++ b/Marlin/src/feature/encoder_i2c.h @@ -90,7 +90,7 @@ #define I2CPE_PARSE_ERR 1 #define I2CPE_PARSE_OK 0 -#define LOOP_PE(VAR) LOOP_L_N(VAR, I2CPE_ENCODER_CNT) +#define LOOP_PE(VAR) for (uint8_t VAR = 0; VAR < I2CPE_ENCODER_CNT; ++VAR) #define CHECK_IDX() do{ if (!WITHIN(idx, 0, I2CPE_ENCODER_CNT - 1)) return; }while(0) typedef union { @@ -188,7 +188,7 @@ class I2CPositionEncoder { FORCE_INLINE void set_ec_method(const byte method) { ecMethod = method; } FORCE_INLINE float get_ec_threshold() { return ecThreshold; } - FORCE_INLINE void set_ec_threshold(const_float_t newThreshold) { ecThreshold = newThreshold; } + FORCE_INLINE void set_ec_threshold(const float newThreshold) { ecThreshold = newThreshold; } FORCE_INLINE int get_encoder_ticks_mm() { switch (type) { @@ -261,32 +261,32 @@ class I2CPositionEncodersMgr { static void report_error_count(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); - SERIAL_ECHOLNPGM("Error count on ", AS_CHAR(AXIS_CHAR(axis)), " axis is ", encoders[idx].get_error_count()); + SERIAL_ECHOLNPGM("Error count on ", C(AXIS_CHAR(axis)), " axis is ", encoders[idx].get_error_count()); } static void reset_error_count(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_error_count(0); - SERIAL_ECHOLNPGM("Error count on ", AS_CHAR(AXIS_CHAR(axis)), " axis has been reset."); + SERIAL_ECHOLNPGM("Error count on ", C(AXIS_CHAR(axis)), " axis has been reset."); } static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_ec_enabled(enabled); - SERIAL_ECHOPGM("Error correction on ", AS_CHAR(AXIS_CHAR(axis))); + SERIAL_ECHOPGM("Error correction on ", C(AXIS_CHAR(axis))); SERIAL_ECHO_TERNARY(encoders[idx].get_ec_enabled(), " axis is ", "en", "dis", "abled.\n"); } static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_ec_threshold(newThreshold); - SERIAL_ECHOLNPGM("Error correct threshold for ", AS_CHAR(AXIS_CHAR(axis)), " axis set to ", newThreshold, "mm."); + SERIAL_ECHOLNPGM("Error correct threshold for ", C(AXIS_CHAR(axis)), " axis set to ", newThreshold, "mm."); } static void get_ec_threshold(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); const float threshold = encoders[idx].get_ec_threshold(); - SERIAL_ECHOLNPGM("Error correct threshold for ", AS_CHAR(AXIS_CHAR(axis)), " axis is ", threshold, "mm."); + SERIAL_ECHOLNPGM("Error correct threshold for ", C(AXIS_CHAR(axis)), " axis is ", threshold, "mm."); } static int8_t idx_from_axis(const AxisEnum axis) { diff --git a/Marlin/src/feature/ethernet.cpp b/Marlin/src/feature/ethernet.cpp index c5bfa932cb..cdf176f832 100644 --- a/Marlin/src/feature/ethernet.cpp +++ b/Marlin/src/feature/ethernet.cpp @@ -141,7 +141,7 @@ void MarlinEthernet::check() { case CONNECTING: telnetClient.println("Marlin " SHORT_BUILD_VERSION); - #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) + #ifdef STRING_DISTRIBUTION_DATE telnetClient.println( " Last Updated: " STRING_DISTRIBUTION_DATE " | Author: " STRING_CONFIG_H_AUTHOR @@ -172,4 +172,46 @@ void MarlinEthernet::check() { } } +void say_ethernet() { SERIAL_ECHOPGM(" Ethernet "); } + +void MarlinEthernet::ETH0_report(const bool forReplay/*=true*/) { + say_ethernet(); + SERIAL_ECHO_TERNARY(ethernet.hardware_enabled, "port ", "en", "dis", "abled.\n"); + if (ethernet.hardware_enabled) { + say_ethernet(); + SERIAL_ECHO_TERNARY(ethernet.have_telnet_client, "client ", "en", "dis", "abled.\n"); + } + else + SERIAL_ECHOLNPGM("Send 'M552 S1' to enable."); +} + +void MarlinEthernet::MAC_report(const bool forReplay/*=true*/) { + if (!forReplay) SERIAL_ECHO_START(); + SERIAL_ECHOPGM("MAC: "); + if (ethernet.hardware_enabled) { + uint8_t mac[6]; + Ethernet.MACAddress(mac); + for (uint8_t i = 0; i < 6; ++i) { + if (mac[i] < 0x10) SERIAL_CHAR('0'); + SERIAL_PRINT(mac[i], PrintBase::Hex); + if (i < 5) SERIAL_CHAR(':'); + } + } + else + SERIAL_ECHOPGM("Disabled"); + SERIAL_EOL(); +} + +// Display current values when the link is active, +// otherwise show the stored values +void MarlinEthernet::ip_report(const uint16_t cmd, FSTR_P const post, const IPAddress &ipo, const bool forReplay/*=true*/) { + if (!forReplay) SERIAL_ECHO_START(); + SERIAL_ECHO(F(" M"), cmd, C(' ')); + for (uint8_t i = 0; i < 4; ++i) { + SERIAL_ECHO(ipo[i]); + if (i < 3) SERIAL_CHAR('.'); + } + SERIAL_ECHOLN(F(" ; "), post); +} + #endif // HAS_ETHERNET diff --git a/Marlin/src/feature/ethernet.h b/Marlin/src/feature/ethernet.h index 70a58efce7..7aa364fc3c 100644 --- a/Marlin/src/feature/ethernet.h +++ b/Marlin/src/feature/ethernet.h @@ -25,6 +25,8 @@ #include #endif +#include "../HAL/shared/Marduino.h" + // Teensy 4.1 uses internal MAC Address class MarlinEthernet { @@ -34,6 +36,10 @@ class MarlinEthernet { static EthernetClient telnetClient; static void init(); static void check(); + + static void ETH0_report(const bool forReplay=true); + static void MAC_report(const bool forReplay=true); + static void ip_report(const uint16_t cmd, FSTR_P const post, const IPAddress &ipo, const bool forReplay=true); }; extern MarlinEthernet ethernet; diff --git a/Marlin/src/feature/fancheck.cpp b/Marlin/src/feature/fancheck.cpp index 126b79b0a4..d0582ed97a 100644 --- a/Marlin/src/feature/fancheck.cpp +++ b/Marlin/src/feature/fancheck.cpp @@ -42,62 +42,18 @@ bool FanCheck::enabled; void FanCheck::init() { #define _TACHINIT(N) TERN(E##N##_FAN_TACHO_PULLUP, SET_INPUT_PULLUP, TERN(E##N##_FAN_TACHO_PULLDOWN, SET_INPUT_PULLDOWN, SET_INPUT))(E##N##_FAN_TACHO_PIN) - #if HAS_E0_FAN_TACHO - _TACHINIT(0); - #endif - #if HAS_E1_FAN_TACHO - _TACHINIT(1); - #endif - #if HAS_E2_FAN_TACHO - _TACHINIT(2); - #endif - #if HAS_E3_FAN_TACHO - _TACHINIT(3); - #endif - #if HAS_E4_FAN_TACHO - _TACHINIT(4); - #endif - #if HAS_E5_FAN_TACHO - _TACHINIT(5); - #endif - #if HAS_E6_FAN_TACHO - _TACHINIT(6); - #endif - #if HAS_E7_FAN_TACHO - _TACHINIT(7); - #endif + #define _EN_TACHINIT(N) TERF(HAS_E##N##_FAN_TACHO, _TACHINIT)(N); + REPEAT(8, _EN_TACHINIT); } void FanCheck::update_tachometers() { bool status; - #define _TACHO_CASE(N) case N: status = READ(E##N##_FAN_TACHO_PIN); break; - LOOP_L_N(f, TACHO_COUNT) { + #define __TACHO_GET_STATUS(N) case N: status = READ(E##N##_FAN_TACHO_PIN); break; + #define _TACHO_GET_STATUS(N) TERF(HAS_E##N##_FAN_TACHO, __TACHO_GET_STATUS)(N) + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { - #if HAS_E0_FAN_TACHO - _TACHO_CASE(0) - #endif - #if HAS_E1_FAN_TACHO - _TACHO_CASE(1) - #endif - #if HAS_E2_FAN_TACHO - _TACHO_CASE(2) - #endif - #if HAS_E3_FAN_TACHO - _TACHO_CASE(3) - #endif - #if HAS_E4_FAN_TACHO - _TACHO_CASE(4) - #endif - #if HAS_E5_FAN_TACHO - _TACHO_CASE(5) - #endif - #if HAS_E6_FAN_TACHO - _TACHO_CASE(6) - #endif - #if HAS_E7_FAN_TACHO - _TACHO_CASE(7) - #endif + REPEAT(8, _TACHO_GET_STATUS) default: continue; } @@ -113,16 +69,10 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { static uint8_t fan_reported_errors_msk = 0; uint8_t fan_error_msk = 0; - LOOP_L_N(f, TACHO_COUNT) { + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { - TERN_(HAS_E0_FAN_TACHO, case 0:) - TERN_(HAS_E1_FAN_TACHO, case 1:) - TERN_(HAS_E2_FAN_TACHO, case 2:) - TERN_(HAS_E3_FAN_TACHO, case 3:) - TERN_(HAS_E4_FAN_TACHO, case 4:) - TERN_(HAS_E5_FAN_TACHO, case 5:) - TERN_(HAS_E6_FAN_TACHO, case 6:) - TERN_(HAS_E7_FAN_TACHO, case 7:) + #define _EN_COMPUTE_FAN_CASE(N) TERN_(HAS_E##N##_FAN_TACHO, case N:) + REPEAT(8, _EN_COMPUTE_FAN_CASE) // Compute fan speed rps[f] = edge_counter[f] * float(250) / elapsedTime; edge_counter[f] = 0; @@ -143,30 +93,30 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { // Drop the error when all fans are ok if (!fan_error_msk && error == TachoError::REPORTED) error = TachoError::FIXED; - if (error == TachoError::FIXED && !printJobOngoing() && !printingIsPaused()) { + if (error == TachoError::FIXED && !marlin.printJobOngoing() && !marlin.printingIsPaused()) { error = TachoError::NONE; // if the issue has been fixed while the printer is idle, reenable immediately ui.reset_alert_level(); } if (fan_error_msk & ~fan_reported_errors_msk) { // Handle new faults only - LOOP_L_N(f, TACHO_COUNT) if (TEST(fan_error_msk, f)) report_speed_error(f); + for (uint8_t f = 0; f < TACHO_COUNT; ++f) if (TEST(fan_error_msk, f)) report_speed_error(f); } fan_reported_errors_msk = fan_error_msk; } void FanCheck::report_speed_error(uint8_t fan) { - if (printJobOngoing()) { + if (marlin.printJobOngoing()) { if (error == TachoError::NONE) { if (thermalManager.degTargetHotend(fan) != 0) { - kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT)); + marlin.kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT)); error = TachoError::REPORTED; } else error = TachoError::DETECTED; // Plans error for next processed command } } - else if (!printingIsPaused()) { + else if (!marlin.printingIsPaused()) { thermalManager.setTargetHotend(0, fan); // Always disable heating if (error == TachoError::NONE) error = TachoError::REPORTED; } @@ -176,17 +126,11 @@ void FanCheck::report_speed_error(uint8_t fan) { } void FanCheck::print_fan_states() { - LOOP_L_N(s, 2) { - LOOP_L_N(f, TACHO_COUNT) { + for (uint8_t s = 0; s < 2; ++s) { + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { - TERN_(HAS_E0_FAN_TACHO, case 0:) - TERN_(HAS_E1_FAN_TACHO, case 1:) - TERN_(HAS_E2_FAN_TACHO, case 2:) - TERN_(HAS_E3_FAN_TACHO, case 3:) - TERN_(HAS_E4_FAN_TACHO, case 4:) - TERN_(HAS_E5_FAN_TACHO, case 5:) - TERN_(HAS_E6_FAN_TACHO, case 6:) - TERN_(HAS_E7_FAN_TACHO, case 7:) + #define _EN_PRINT_FAN_CASE(N) TERN_(HAS_E##N##_FAN_TACHO, case N:) + REPEAT(8, _EN_PRINT_FAN_CASE) SERIAL_ECHOPGM("E", f); if (s == 0) SERIAL_ECHOPGM(":", 60 * rps[f], " RPM "); diff --git a/Marlin/src/feature/fancheck.h b/Marlin/src/feature/fancheck.h index b13a34fb19..fed6a798e1 100644 --- a/Marlin/src/feature/fancheck.h +++ b/Marlin/src/feature/fancheck.h @@ -25,7 +25,6 @@ #if HAS_FANCHECK -#include "../MarlinCore.h" #include "../lcd/marlinui.h" #if ENABLED(AUTO_REPORT_FANS) @@ -67,14 +66,18 @@ class FanCheck { static void compute_speed(uint16_t elapsedTime); static void print_fan_states(); #if HAS_PWMFANCHECK - static void toggle_measuring() { measuring = !measuring; } + static void toggle_measuring() { FLIP(measuring); } static bool is_measuring() { return measuring; } #endif static void check_deferred_error() { if (error == TachoError::DETECTED) { error = TachoError::REPORTED; - TERN(PARK_HEAD_ON_PAUSE, queue.inject(F("M125")), kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT))); + #if ENABLED(PARK_HEAD_ON_PAUSE) + queue.inject(F("M125")); + #else + marlin.kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT)); + #endif } } diff --git a/Marlin/src/feature/filwidth.cpp b/Marlin/src/feature/filwidth.cpp index 2bd9c78980..1142423cf7 100644 --- a/Marlin/src/feature/filwidth.cpp +++ b/Marlin/src/feature/filwidth.cpp @@ -28,7 +28,7 @@ FilamentWidthSensor filwidth; -bool FilamentWidthSensor::enabled; // = false; // (M405-M406) Filament Width Sensor ON/OFF. +bool FilamentWidthSensor::enabled; // = false // (M405-M406) Filament Width Sensor ON/OFF. uint32_t FilamentWidthSensor::accum; // = 0 // ADC accumulator uint16_t FilamentWidthSensor::raw; // = 0 // Measured filament diameter - one extruder only float FilamentWidthSensor::nominal_mm = DEFAULT_NOMINAL_FILAMENT_DIA, // (M104) Nominal filament width @@ -42,7 +42,7 @@ int8_t FilamentWidthSensor::ratios[MAX_MEASUREMENT_DELAY + 1], // Ring void FilamentWidthSensor::init() { const int8_t ratio = sample_to_size_ratio(); - LOOP_L_N(i, COUNT(ratios)) ratios[i] = ratio; + for (uint8_t i = 0; i < COUNT(ratios); ++i) ratios[i] = ratio; index_r = index_w = 0; } diff --git a/Marlin/src/feature/filwidth.h b/Marlin/src/feature/filwidth.h index 9eb1e77762..a16240936a 100644 --- a/Marlin/src/feature/filwidth.h +++ b/Marlin/src/feature/filwidth.h @@ -67,7 +67,7 @@ public: } // Convert raw measurement to mm - static float raw_to_mm(const uint16_t v) { return v * float(ADC_VREF) * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); } + static float raw_to_mm(const uint16_t v) { return v * (float(ADC_VREF_MV) * 0.001f) * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); } static float raw_to_mm() { return raw_to_mm(raw); } // A scaled reading is ready @@ -78,7 +78,7 @@ public: static void update_measured_mm() { measured_mm = raw_to_mm(); } // Update ring buffer used to delay filament measurements - static void advance_e(const_float_t e_move) { + static void advance_e(const float e_move) { // Increment counters with the E distance e_count += e_move; diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 28355640d2..5ea20401ea 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -137,7 +137,7 @@ void FWRetract::retract(const bool retracting E_OPTARG(bool swapping/*=false*/)) // Retract by moving from a faux E position back to the current E position current_retract[active_extruder] = base_retract; prepare_internal_move_to_destination( // set current from destination - settings.retract_feedrate_mm_s * TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS)) + MUL_TERN(RETRACT_SYNC_MIXING, settings.retract_feedrate_mm_s, MIXING_STEPPERS) ); // Is a Z hop set, and has the hop not yet been done? @@ -164,10 +164,8 @@ void FWRetract::retract(const bool retracting E_OPTARG(bool swapping/*=false*/)) current_retract[active_extruder] = 0; // Recover E, set_current_to_destination - prepare_internal_move_to_destination( - (swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s) - * TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS)) - ); + const feedRate_t fr_mm_s = swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s; + prepare_internal_move_to_destination(MUL_TERN(RETRACT_SYNC_MIXING, fr_mm_s, MIXING_STEPPERS)); } TERN_(RETRACT_SYNC_MIXING, mixer.T(old_mixing_tool)); // Restore original mixing tool @@ -195,8 +193,6 @@ void FWRetract::retract(const bool retracting E_OPTARG(bool swapping/*=false*/)) //*/ } -//extern const char SP_Z_STR[]; - /** * M207: Set firmware retraction values * @@ -214,6 +210,8 @@ void FWRetract::M207() { } void FWRetract::M207_report() { + TERN_(MARLIN_SMALL_BUILD, return); + SERIAL_ECHOLNPGM_P( PSTR(" M207 S"), LINEAR_UNIT(settings.retract_length) , PSTR(" W"), LINEAR_UNIT(settings.swap_retract_length) @@ -239,10 +237,13 @@ void FWRetract::M208() { } void FWRetract::M208_report() { + TERN_(MARLIN_SMALL_BUILD, return); + SERIAL_ECHOLNPGM( " M208 S", LINEAR_UNIT(settings.retract_recover_extra) , " W", LINEAR_UNIT(settings.swap_retract_recover_extra) , " F", LINEAR_UNIT(MMS_TO_MMM(settings.retract_recover_feedrate_mm_s)) + , " R", LINEAR_UNIT(MMS_TO_MMM(settings.swap_retract_recover_feedrate_mm_s)) ); } @@ -260,10 +261,11 @@ void FWRetract::M208_report() { } void FWRetract::M209_report() { + TERN_(MARLIN_SMALL_BUILD, return); + SERIAL_ECHOLNPGM(" M209 S", AS_DIGIT(autoretract_enabled)); } #endif // FWRETRACT_AUTORETRACT - #endif // FWRETRACT diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index c03a6bc597..94bc4db011 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -41,8 +41,7 @@ HostUI hostui; void HostUI::action(FSTR_P const fstr, const bool eol) { PORT_REDIRECT(SerialMask::All); - SERIAL_ECHOPGM("//action:"); - SERIAL_ECHOF(fstr); + SERIAL_ECHOPGM("//action:", fstr); if (eol) SERIAL_EOL(); } @@ -88,10 +87,6 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { PGMSTR(CONTINUE_STR, "Continue"); PGMSTR(DISMISS_STR, "Dismiss"); - #if HAS_RESUME_CONTINUE - extern bool wait_for_user; - #endif - void HostUI::notify(const char * const cstr) { PORT_REDIRECT(SerialMask::All); action(F("notification "), false); @@ -107,24 +102,33 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { void HostUI::prompt(FSTR_P const ptype, const bool eol/*=true*/) { PORT_REDIRECT(SerialMask::All); action(F("prompt_"), false); - SERIAL_ECHOF(ptype); + SERIAL_ECHO(ptype); if (eol) SERIAL_EOL(); } - void HostUI::prompt_plus(FSTR_P const ptype, FSTR_P const fstr, const char extra_char/*='\0'*/) { + void HostUI::prompt_plus(const bool pgm, FSTR_P const ptype, const char * const str, const char extra_char/*='\0'*/) { prompt(ptype, false); PORT_REDIRECT(SerialMask::All); SERIAL_CHAR(' '); - SERIAL_ECHOF(fstr); + if (pgm) + SERIAL_ECHOPGM_P(str); + else + SERIAL_ECHO(str); if (extra_char != '\0') SERIAL_CHAR(extra_char); SERIAL_EOL(); } + void HostUI::prompt_begin(const PromptReason reason, FSTR_P const fstr, const char extra_char/*='\0'*/) { prompt_end(); host_prompt_reason = reason; prompt_plus(F("begin"), fstr, extra_char); } - void HostUI::prompt_button(FSTR_P const fstr) { prompt_plus(F("button"), fstr); } + void HostUI::prompt_begin(const PromptReason reason, const char * const cstr, const char extra_char/*='\0'*/) { + prompt_end(); + host_prompt_reason = reason; + prompt_plus(F("begin"), cstr, extra_char); + } + void HostUI::prompt_end() { prompt(F("end")); } void HostUI::prompt_show() { prompt(F("show")); } @@ -133,14 +137,26 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { if (btn2) prompt_button(btn2); prompt_show(); } + + void HostUI::prompt_button(FSTR_P const fstr) { prompt_plus(F("button"), fstr); } + void HostUI::prompt_button(const char * const cstr) { prompt_plus(F("button"), cstr); } + void HostUI::prompt_do(const PromptReason reason, FSTR_P const fstr, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) { prompt_begin(reason, fstr); _prompt_show(btn1, btn2); } + void HostUI::prompt_do(const PromptReason reason, const char * const cstr, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) { + prompt_begin(reason, cstr); + _prompt_show(btn1, btn2); + } void HostUI::prompt_do(const PromptReason reason, FSTR_P const fstr, const char extra_char, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) { prompt_begin(reason, fstr, extra_char); _prompt_show(btn1, btn2); } + void HostUI::prompt_do(const PromptReason reason, const char * const cstr, const char extra_char, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) { + prompt_begin(reason, cstr, extra_char); + _prompt_show(btn1, btn2); + } #if ENABLED(ADVANCED_PAUSE_FEATURE) void HostUI::filament_load_prompt() { @@ -166,13 +182,13 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { switch (response) { case 0: // "Purge More" button - #if BOTH(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) + #if ENABLED(M600_PURGE_MORE_RESUMABLE) pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; // Simulate menu selection (menu exits, doesn't extrude more) #endif break; case 1: // "Continue" / "Disable Runout" button - #if BOTH(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) + #if ENABLED(M600_PURGE_MORE_RESUMABLE) pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; // Simulate menu selection #endif #if HAS_FILAMENT_SENSOR @@ -185,10 +201,10 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { } break; case PROMPT_USER_CONTINUE: - TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); + TERN_(HAS_RESUME_CONTINUE, marlin.user_resume()); break; case PROMPT_PAUSE_RESUME: - #if BOTH(ADVANCED_PAUSE_FEATURE, SDSUPPORT) + #if ALL(ADVANCED_PAUSE_FEATURE, HAS_MEDIA) extern const char M24_STR[]; queue.inject_P(M24_STR); #endif diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index 41d66b82ec..c030ebad01 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -35,6 +35,8 @@ PROMPT_INFO }; + extern const char CONTINUE_STR[], DISMISS_STR[]; + #endif class HostUI { @@ -79,7 +81,14 @@ class HostUI { #if ENABLED(HOST_PROMPT_SUPPORT) private: static void prompt(FSTR_P const ptype, const bool eol=true); - static void prompt_plus(FSTR_P const ptype, FSTR_P const fstr, const char extra_char='\0'); + static void prompt_plus(const bool pgm, FSTR_P const ptype, const char * const str, const char extra_char='\0'); + static void prompt_plus(FSTR_P const ptype, FSTR_P const fstr, const char extra_char='\0') { + prompt_plus(true, ptype, FTOP(fstr), extra_char); + } + static void prompt_plus(FSTR_P const ptype, const char * const cstr, const char extra_char='\0') { + prompt_plus(false, ptype, cstr, extra_char); + } + static void prompt_show(); static void _prompt_show(FSTR_P const btn1, FSTR_P const btn2); @@ -93,10 +102,20 @@ class HostUI { static void notify(const char * const message); static void prompt_begin(const PromptReason reason, FSTR_P const fstr, const char extra_char='\0'); - static void prompt_button(FSTR_P const fstr); + static void prompt_begin(const PromptReason reason, const char * const cstr, const char extra_char='\0'); static void prompt_end(); + + static void prompt_button(FSTR_P const fstr); + static void prompt_button(const char * const cstr); + static void prompt_do(const PromptReason reason, FSTR_P const pstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr); + static void prompt_do(const PromptReason reason, const char * const cstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr); static void prompt_do(const PromptReason reason, FSTR_P const pstr, const char extra_char, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr); + static void prompt_do(const PromptReason reason, const char * const cstr, const char extra_char, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr); + + static void continue_prompt(FSTR_P const fstr) { prompt_do(PROMPT_USER_CONTINUE, fstr, FPSTR(CONTINUE_STR)); } + static void continue_prompt(const char * const cstr) { prompt_do(PROMPT_USER_CONTINUE, cstr, FPSTR(CONTINUE_STR)); } + static void prompt_open(const PromptReason reason, FSTR_P const pstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr) { if (host_prompt_reason == PROMPT_NOT_DEFINED) prompt_do(reason, pstr, btn1, btn2); } @@ -110,5 +129,3 @@ class HostUI { }; extern HostUI hostui; - -extern const char CONTINUE_STR[], DISMISS_STR[]; diff --git a/Marlin/src/feature/hotend_idle.cpp b/Marlin/src/feature/hotend_idle.cpp index 4b137f42da..a779efeaff 100644 --- a/Marlin/src/feature/hotend_idle.cpp +++ b/Marlin/src/feature/hotend_idle.cpp @@ -37,28 +37,33 @@ #include "../module/planner.h" #include "../lcd/marlinui.h" -extern HotendIdleProtection hotend_idle; +HotendIdleProtection hotend_idle; millis_t HotendIdleProtection::next_protect_ms = 0; +hotend_idle_settings_t HotendIdleProtection::cfg; // Initialized by settings.load void HotendIdleProtection::check_hotends(const millis_t &ms) { + const bool busy = (TERN0(HAS_RESUME_CONTINUE, marlin.wait_for_user) || planner.has_blocks_queued()); bool do_prot = false; - HOTEND_LOOP() { - const bool busy = (TERN0(HAS_RESUME_CONTINUE, wait_for_user) || planner.has_blocks_queued()); - if (thermalManager.degHotend(e) >= (HOTEND_IDLE_MIN_TRIGGER) && !busy) { - do_prot = true; break; + if (!busy && cfg.timeout != 0) { + HOTEND_LOOP() { + if (thermalManager.degHotend(e) >= cfg.trigger) { + do_prot = true; break; + } } } - if (bool(next_protect_ms) != do_prot) - next_protect_ms = do_prot ? ms + hp_interval : 0; + if (!do_prot) + next_protect_ms = 0; // No hotends are hot so cancel timeout + else if (!next_protect_ms) // Timeout is possible? + next_protect_ms = ms + 1000UL * cfg.timeout; // Start timeout if not already set } void HotendIdleProtection::check_e_motion(const millis_t &ms) { static float old_e_position = 0; if (old_e_position != current_position.e) { - old_e_position = current_position.e; // Track filament motion - if (next_protect_ms) // If some heater is on then... - next_protect_ms = ms + hp_interval; // ...delay the timeout till later + old_e_position = current_position.e; // Track filament motion + if (next_protect_ms) // If some heater is on then... + next_protect_ms = ms + 1000UL * cfg.timeout; // ...delay the timeout till later } } @@ -79,12 +84,12 @@ void HotendIdleProtection::timed_out() { SERIAL_ECHOLNPGM("Hotend Idle Timeout"); LCD_MESSAGE(MSG_HOTEND_IDLE_TIMEOUT); HOTEND_LOOP() { - if ((HOTEND_IDLE_NOZZLE_TARGET) < thermalManager.degTargetHotend(e)) - thermalManager.setTargetHotend(HOTEND_IDLE_NOZZLE_TARGET, e); + if (cfg.nozzle_target < thermalManager.degTargetHotend(e)) + thermalManager.setTargetHotend(cfg.nozzle_target, e); } #if HAS_HEATED_BED - if ((HOTEND_IDLE_BED_TARGET) < thermalManager.degTargetBed()) - thermalManager.setTargetBed(HOTEND_IDLE_BED_TARGET); + if (cfg.bed_target < thermalManager.degTargetBed()) + thermalManager.setTargetBed(cfg.bed_target); #endif } diff --git a/Marlin/src/feature/hotend_idle.h b/Marlin/src/feature/hotend_idle.h index 40f557d5ed..d215e27bc5 100644 --- a/Marlin/src/feature/hotend_idle.h +++ b/Marlin/src/feature/hotend_idle.h @@ -21,13 +21,28 @@ */ #pragma once -#include "../core/millis_t.h" +#include "../inc/MarlinConfig.h" + +typedef struct { + int16_t timeout, trigger, nozzle_target; + #if HAS_HEATED_BED + int16_t bed_target; + #endif + void set_defaults() { + timeout = HOTEND_IDLE_TIMEOUT_SEC; + trigger = HOTEND_IDLE_MIN_TRIGGER; + nozzle_target = HOTEND_IDLE_NOZZLE_TARGET; + #if HAS_HEATED_BED + bed_target = HOTEND_IDLE_BED_TARGET; + #endif + } +} hotend_idle_settings_t; class HotendIdleProtection { public: static void check(); + static hotend_idle_settings_t cfg; private: - static constexpr millis_t hp_interval = SEC_TO_MS(HOTEND_IDLE_TIMEOUT_SEC); static millis_t next_protect_ms; static void check_hotends(const millis_t &ms); static void check_e_motion(const millis_t &ms); diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index acab5d7437..cbfab1fed8 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/Marlin/src/feature/joystick.cpp @@ -67,18 +67,10 @@ Joystick joystick; #if ENABLED(JOYSTICK_DEBUG) void Joystick::report() { SERIAL_ECHOPGM("Joystick"); - #if HAS_JOY_ADC_X - SERIAL_ECHOPGM_P(SP_X_STR, JOY_X(x.getraw())); - #endif - #if HAS_JOY_ADC_Y - SERIAL_ECHOPGM_P(SP_Y_STR, JOY_Y(y.getraw())); - #endif - #if HAS_JOY_ADC_Z - SERIAL_ECHOPGM_P(SP_Z_STR, JOY_Z(z.getraw())); - #endif - #if HAS_JOY_ADC_EN - SERIAL_ECHO_TERNARY(READ(JOY_EN_PIN), " EN=", "HIGH (dis", "LOW (en", "abled)"); - #endif + TERF(HAS_JOY_ADC_X, SERIAL_ECHOPGM_P)(SP_X_STR, JOY_X(x.getraw())); + TERF(HAS_JOY_ADC_Y, SERIAL_ECHOPGM_P)(SP_Y_STR, JOY_Y(y.getraw())); + TERF(HAS_JOY_ADC_Z, SERIAL_ECHOPGM_P)(SP_Z_STR, JOY_Z(z.getraw())); + TERF(HAS_JOY_ADC_EN, SERIAL_ECHO_TERNARY)(READ(JOY_EN_PIN), " EN=", "HIGH (dis", "LOW (en", "abled)"); SERIAL_EOL(); } #endif @@ -123,7 +115,7 @@ Joystick joystick; void Joystick::inject_jog_moves() { // Recursion barrier - static bool injecting_now; // = false; + static bool injecting_now; // = false if (injecting_now) return; #if ENABLED(NO_MOTION_BEFORE_HOMING) diff --git a/Marlin/src/feature/leds/blinkm.cpp b/Marlin/src/feature/leds/blinkm.cpp index 868eb4b3d9..b040c8e76f 100644 --- a/Marlin/src/feature/leds/blinkm.cpp +++ b/Marlin/src/feature/leds/blinkm.cpp @@ -32,7 +32,7 @@ #include "leds.h" #include -void blinkm_set_led_color(const LEDColor &color) { +void blinkm_set_led_color(const LED1Color_t &color) { Wire.begin(); Wire.beginTransmission(I2C_ADDRESS(0x09)); Wire.write('o'); //to disable ongoing script, only needs to be used once diff --git a/Marlin/src/feature/leds/blinkm.h b/Marlin/src/feature/leds/blinkm.h index 29a9e78412..d3c528acbf 100644 --- a/Marlin/src/feature/leds/blinkm.h +++ b/Marlin/src/feature/leds/blinkm.h @@ -25,7 +25,6 @@ * blinkm.h - Control a BlinkM over i2c */ -struct LEDColor; -typedef LEDColor LEDColor; +struct LED1Color_t; -void blinkm_set_led_color(const LEDColor &color); +void blinkm_set_led_color(const LED1Color_t &color); diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 2a53a7c884..55a10fcbbd 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -30,60 +30,141 @@ #include "leds.h" -#if ENABLED(BLINKM) - #include "blinkm.h" -#endif - -#if ENABLED(PCA9632) - #include "pca9632.h" -#endif - -#if ENABLED(PCA9533) - #include "pca9533.h" -#endif - -#if EITHER(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL) - #include "../../feature/caselight.h" +#if ANY(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL) + #include "../caselight.h" #endif #if ENABLED(LED_COLOR_PRESETS) - const LEDColor LEDLights::defaultLEDColor = LEDColor( + const LED1Color_t LEDLights::defaultLEDColor { LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE OPTARG(HAS_WHITE_LED, LED_USER_PRESET_WHITE) OPTARG(NEOPIXEL_LED, LED_USER_PRESET_BRIGHTNESS) - ); + }; #endif #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED) - LEDColor LEDLights::color; + LED1Color_t LEDLights::color; bool LEDLights::lights_on; #endif LEDLights leds; void LEDLights::setup() { - #if EITHER(RGB_LED, RGBW_LED) + #if ANY(RGB_LED, RGBW_LED) if (PWM_PIN(RGB_LED_R_PIN)) SET_PWM(RGB_LED_R_PIN); else SET_OUTPUT(RGB_LED_R_PIN); if (PWM_PIN(RGB_LED_G_PIN)) SET_PWM(RGB_LED_G_PIN); else SET_OUTPUT(RGB_LED_G_PIN); if (PWM_PIN(RGB_LED_B_PIN)) SET_PWM(RGB_LED_B_PIN); else SET_OUTPUT(RGB_LED_B_PIN); #if ENABLED(RGBW_LED) if (PWM_PIN(RGB_LED_W_PIN)) SET_PWM(RGB_LED_W_PIN); else SET_OUTPUT(RGB_LED_W_PIN); #endif - #endif + + #if ENABLED(RGB_STARTUP_TEST) + int8_t led_pin_count = 0; + if (PWM_PIN(RGB_LED_R_PIN) && PWM_PIN(RGB_LED_G_PIN) && PWM_PIN(RGB_LED_B_PIN)) led_pin_count = 3; + #if ENABLED(RGBW_LED) + if (PWM_PIN(RGB_LED_W_PIN) && led_pin_count) led_pin_count++; + #endif + // Startup animation + if (led_pin_count) { + // blackout + if (PWM_PIN(RGB_LED_R_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_R_PIN), 0); else WRITE(RGB_LED_R_PIN, LOW); + if (PWM_PIN(RGB_LED_G_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_G_PIN), 0); else WRITE(RGB_LED_G_PIN, LOW); + if (PWM_PIN(RGB_LED_B_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_B_PIN), 0); else WRITE(RGB_LED_B_PIN, LOW); + #if ENABLED(RGBW_LED) + if (PWM_PIN(RGB_LED_W_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_W_PIN), 0); + else WRITE(RGB_LED_W_PIN, LOW); + #endif + delay(200); + + for (uint8_t i = 0; i < led_pin_count; ++i) { + for (uint8_t b = 0; b <= 200; ++b) { + const uint16_t led_pwm = b <= 100 ? b : 200 - b; + if (i == 0 && PWM_PIN(RGB_LED_R_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_R_PIN), led_pwm); else WRITE(RGB_LED_R_PIN, b < 100 ? HIGH : LOW); + if (i == 1 && PWM_PIN(RGB_LED_G_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_G_PIN), led_pwm); else WRITE(RGB_LED_G_PIN, b < 100 ? HIGH : LOW); + if (i == 2 && PWM_PIN(RGB_LED_B_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_B_PIN), led_pwm); else WRITE(RGB_LED_B_PIN, b < 100 ? HIGH : LOW); + #if ENABLED(RGBW_LED) + if (i == 3) { + if (PWM_PIN(RGB_LED_W_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_W_PIN), led_pwm); + else WRITE(RGB_LED_W_PIN, b < 100 ? HIGH : LOW); + delay(RGB_STARTUP_TEST_INNER_MS);//More slowing for ending + } + #endif + delay(RGB_STARTUP_TEST_INNER_MS); + } + } + delay(500); + } + #endif // RGB_STARTUP_TEST + + #elif ALL(PCA9632, RGB_STARTUP_TEST) // PCA9632 RGB_STARTUP_TEST + + constexpr int8_t led_pin_count = TERN(HAS_WHITE_LED, 4, 3); + + // Startup animation + LED1Color_t curColor = LEDColorOff(); + PCA9632_set_led_color(curColor); // blackout + delay(200); + + /** + * LED Pin Counter steps -> events + * | 0-100 | 100-200 | 200-300 | 300-400 | + * fade in steady | fade out + * start next pin fade in + */ + + uint16_t led_pin_counters[led_pin_count] = { 1, 0, 0 }; + + bool canEnd = false; + while (led_pin_counters[0] != 99 || !canEnd) { + if (led_pin_counters[0] == 99) // End loop next time pin0 counter is 99 + canEnd = true; + for (uint8_t i = 0; i < led_pin_count; ++i) { + if (led_pin_counters[i] > 0) { + if (++led_pin_counters[i] == 400) // turn off current pin counter in led_pin_counters + led_pin_counters[i] = 0; + else if (led_pin_counters[i] == 201) { // start next pin pwm + led_pin_counters[i + 1 == led_pin_count ? 0 : i + 1] = 1; + i++; // skip next pin in this loop so it doesn't increment twice + } + } + } + uint16_t r, g, b; + r = led_pin_counters[0]; curColor.r = r <= 100 ? r : r <= 300 ? 100 : 400 - r; + g = led_pin_counters[1]; curColor.g = g <= 100 ? g : g <= 300 ? 100 : 400 - g; + b = led_pin_counters[2]; curColor.b = b <= 100 ? b : b <= 300 ? 100 : 400 - b; + #if HAS_WHITE_LED + const uint16_t w = led_pin_counters[3]; curColor.w = w <= 100 ? w : w <= 300 ? 100 : 400 - w; + #endif + PCA9632_set_led_color(curColor); + delay(RGB_STARTUP_TEST_INNER_MS); + } + + // Fade to white + for (uint8_t led_pwm = 0; led_pwm <= 100; ++led_pwm) { + NOLESS(curColor.r, led_pwm); + NOLESS(curColor.g, led_pwm); + NOLESS(curColor.b, led_pwm); + TERN_(HAS_WHITE_LED, NOLESS(curColor.w, led_pwm)); + PCA9632_set_led_color(curColor); + delay(RGB_STARTUP_TEST_INNER_MS); + } + + #endif // PCA9632 && RGB_STARTUP_TEST + TERN_(NEOPIXEL_LED, neo.init()); TERN_(PCA9533, PCA9533_init()); TERN_(LED_USER_PRESET_STARTUP, set_default()); } -void LEDLights::set_color(const LEDColor &incol +void LEDLights::set_color(const LED1Color_t &incol OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence/*=false*/) ) { #if ENABLED(NEOPIXEL_LED) const uint32_t neocolor = LEDColorWhite() == incol - ? neo.Color(NEO_WHITE) - : neo.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_LED, incol.w)); + ? neo.White() + : neo.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_NEOPIXEL_1, incol.w)); #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) static uint16_t nextLed = 0; @@ -95,7 +176,7 @@ void LEDLights::set_color(const LEDColor &incol #endif #endif - #if BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) // Update brightness only if caselight is ON or switching leds off if (caselight.on || incol.is_off()) #endif @@ -110,7 +191,7 @@ void LEDLights::set_color(const LEDColor &incol } #endif - #if BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) // Update color only if caselight is ON or switching leds off if (caselight.on || incol.is_off()) #endif @@ -125,7 +206,7 @@ void LEDLights::set_color(const LEDColor &incol #endif - #if EITHER(RGB_LED, RGBW_LED) + #if ANY(RGB_LED, RGBW_LED) // This variant uses 3-4 separate pins for the RGB(W) components. // If the pins can do PWM then their intensity will be set. @@ -147,7 +228,7 @@ void LEDLights::set_color(const LEDColor &incol TERN_(PCA9632, PCA9632_set_led_color(incol)); TERN_(PCA9533, PCA9533_set_rgb(incol.r, incol.g, incol.b)); - #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) + #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) // Don't update the color when OFF lights_on = !incol.is_off(); if (lights_on) color = incol; @@ -158,7 +239,7 @@ void LEDLights::set_color(const LEDColor &incol void LEDLights::toggle() { if (lights_on) set_off(); else update(); } #endif -#if LED_POWEROFF_TIMEOUT > 0 +#if HAS_LED_POWEROFF_TIMEOUT millis_t LEDLights::led_off_time; // = 0 @@ -177,7 +258,7 @@ void LEDLights::set_color(const LEDColor &incol #if ENABLED(NEOPIXEL2_SEPARATE) #if ENABLED(NEO2_COLOR_PRESETS) - const LEDColor LEDLights2::defaultLEDColor = LEDColor( + const LED2Color_t LEDLights2::defaultLEDColor2 = LED2Color_t( NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE OPTARG(HAS_WHITE_LED2, NEO2_USER_PRESET_WHITE) OPTARG(NEOPIXEL_LED, NEO2_USER_PRESET_BRIGHTNESS) @@ -185,7 +266,7 @@ void LEDLights::set_color(const LEDColor &incol #endif #if ENABLED(LED_CONTROL_MENU) - LEDColor LEDLights2::color; + LED2Color_t LEDLights2::color; bool LEDLights2::lights_on; #endif @@ -196,10 +277,10 @@ void LEDLights::set_color(const LEDColor &incol TERN_(NEO2_USER_PRESET_STARTUP, set_default()); } - void LEDLights2::set_color(const LEDColor &incol) { - const uint32_t neocolor = LEDColorWhite() == incol - ? neo2.Color(NEO2_WHITE) - : neo2.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_LED2, incol.w)); + void LEDLights2::set_color(const LED2Color_t &incol) { + const uint32_t neocolor = LEDColorWhite2() == incol + ? neo2.White() + : neo2.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_NEOPIXEL_2, incol.w)); neo2.set_brightness(incol.i); neo2.set_color(neocolor); diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index 8649dd014f..3ba3a31cdb 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -29,89 +29,170 @@ #include -// A white component can be passed -#if EITHER(RGBW_LED, PCA9632_RGBW) - #define HAS_WHITE_LED 1 -#endif - #if ENABLED(NEOPIXEL_LED) #define _NEOPIXEL_INCLUDE_ #include "neopixel.h" #undef _NEOPIXEL_INCLUDE_ #endif +#if ENABLED(BLINKM) + #include "blinkm.h" +#endif + +#if ENABLED(PCA9533) + #include "pca9533.h" +#endif + +#if ENABLED(PCA9632) + #include "pca9632.h" +#endif + +#if ANY(RGBW_LED, PCA9632_RGBW, HAS_WHITE_NEOPIXEL_1) + #define HAS_WHITE_LED 1 +#endif +#if HAS_WHITE_NEOPIXEL_2 + #define HAS_WHITE_LED2 1 +#endif + /** * LEDcolor type for use with leds.set_color */ -typedef struct LEDColor { - uint8_t r, g, b - OPTARG(HAS_WHITE_LED, w) - OPTARG(NEOPIXEL_LED, i) - ; +struct LED1Color_t { + // Basic RGB color components + uint8_t r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, i); + // Default constructor - white color + LED1Color_t() : r(255), g(255), b(255) OPTARG(HAS_WHITE_LED, w(255)) OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)){} - LEDColor() : r(255), g(255), b(255) - OPTARG(HAS_WHITE_LED, w(255)) - OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)) - {} + // Copy constructor + LED1Color_t(const LED1Color_t&) = default; - LEDColor(const LEDColor&) = default; - - LEDColor(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS)) + // Constructor with individual components + LED1Color_t(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS)) : r(r), g(g), b(b) OPTARG(HAS_WHITE_LED, w(w)) OPTARG(NEOPIXEL_LED, i(i)) {} - LEDColor(const uint8_t (&rgbw)[4]) : r(rgbw[0]), g(rgbw[1]), b(rgbw[2]) - OPTARG(HAS_WHITE_LED, w(rgbw[3])) - OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)) - {} + // Constructor from array + LED1Color_t(const uint8_t (&rgbw)[4]) : r(rgbw[0]), g(rgbw[1]), b(rgbw[2]) + OPTARG(HAS_WHITE_LED, w(rgbw[3])) OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)){} - LEDColor& operator=(const uint8_t (&rgbw)[4]) { + // Array assignment operator + LED1Color_t& operator=(const uint8_t (&rgbw)[4]) { r = rgbw[0]; g = rgbw[1]; b = rgbw[2]; TERN_(HAS_WHITE_LED, w = rgbw[3]); return *this; } - bool operator==(const LEDColor &right) { - if (this == &right) return true; - return 0 == memcmp(this, &right, sizeof(LEDColor)); + // Comparison operators + bool operator==(const LED1Color_t &right) { + return (this == &right) || (0 == memcmp(this, &right, sizeof(LED1Color_t))); } - bool operator!=(const LEDColor &right) { return !operator==(right); } + bool operator!=(const LED1Color_t &right) { + return !operator==(right); + } + // Check if LED is effectively off bool is_off() const { return 3 > r + g + b + TERN0(HAS_WHITE_LED, w); } -} LEDColor; +}; + + +struct LED2Color_t { + // Basic RGB color components + uint8_t r, g, b OPTARG(HAS_WHITE_LED2, w) OPTARG(NEOPIXEL_LED, i); + // Default constructor - white color + LED2Color_t() : r(255), g(255), b(255) OPTARG(HAS_WHITE_LED2, w(255)) OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)){} + + // Copy constructor + LED2Color_t(const LED2Color_t&) = default; + + // Constructor with individual components + LED2Color_t(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED2, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS)) + : r(r), g(g), b(b) OPTARG(HAS_WHITE_LED2, w(w)) OPTARG(NEOPIXEL_LED, i(i)) {} + + // Constructor from array + LED2Color_t(const uint8_t (&rgbw)[4]) : r(rgbw[0]), g(rgbw[1]), b(rgbw[2]) + OPTARG(HAS_WHITE_LED2, w(rgbw[3])) OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)){} + + // Array assignment operator + LED2Color_t& operator=(const uint8_t (&rgbw)[4]) { + r = rgbw[0]; g = rgbw[1]; b = rgbw[2]; + TERN_(HAS_WHITE_LED2, w = rgbw[3]); + return *this; + } + + // Comparison operators + bool operator==(const LED2Color_t &right) { + return (this == &right) || (0 == memcmp(this, &right, sizeof(LED1Color_t))); + } + + bool operator!=(const LED2Color_t &right) { + return !operator==(right); + } + + // Check if LED is effectively off + bool is_off() const { + return 3 > r + g + b + TERN0(HAS_WHITE_LED2, w); + } +}; /** * Color presets */ -#define LEDColorOff() LEDColor( 0, 0, 0) -#define LEDColorRed() LEDColor(255, 0, 0) +#define LEDColorOff() LED1Color_t( 0, 0, 0) +#define LEDColorRed() LED1Color_t(255, 0, 0) #if ENABLED(LED_COLORS_REDUCE_GREEN) - #define LEDColorOrange() LEDColor(255, 25, 0) - #define LEDColorYellow() LEDColor(255, 75, 0) + #define LEDColorOrange() LED1Color_t(255, 25, 0) + #define LEDColorYellow() LED1Color_t(255, 75, 0) #else - #define LEDColorOrange() LEDColor(255, 80, 0) - #define LEDColorYellow() LEDColor(255, 255, 0) + #define LEDColorOrange() LED1Color_t(255, 80, 0) + #define LEDColorYellow() LED1Color_t(255, 255, 0) #endif -#define LEDColorGreen() LEDColor( 0, 255, 0) -#define LEDColorBlue() LEDColor( 0, 0, 255) -#define LEDColorIndigo() LEDColor( 0, 255, 255) -#define LEDColorViolet() LEDColor(255, 0, 255) +#define LEDColorGreen() LED1Color_t( 0, 255, 0) +#define LEDColorBlue() LED1Color_t( 0, 0, 255) +#define LEDColorIndigo() LED1Color_t( 0, 255, 255) +#define LEDColorViolet() LED1Color_t(255, 0, 255) #if HAS_WHITE_LED && DISABLED(RGB_LED) - #define LEDColorWhite() LEDColor( 0, 0, 0, 255) + #define LEDColorWhite() LED1Color_t( 0, 0, 0, 255) #else - #define LEDColorWhite() LEDColor(255, 255, 255) + #define LEDColorWhite() LED1Color_t(255, 255, 255) #endif +#define LEDColorOff2() LED2Color_t( 0, 0, 0) +#define LEDColorRed2() LED2Color_t(255, 0, 0) +#if ENABLED(LED_COLORS_REDUCE_GREEN) + #define LEDColorOrange2() LED2Color_t(255, 25, 0) + #define LEDColorYellow2() LED2Color_t(255, 75, 0) +#else + #define LEDColorOrange2() LED2Color_t(255, 80, 0) + #define LEDColorYellow2() LED2Color_t(255, 255, 0) +#endif +#define LEDColorGreen2() LED2Color_t( 0, 255, 0) +#define LEDColorBlue2() LED2Color_t( 0, 0, 255) +#define LEDColorIndigo2() LED2Color_t( 0, 255, 255) +#define LEDColorViolet2() LED2Color_t(255, 0, 255) +#if HAS_WHITE_LED2 && DISABLED(RGB_LED) + #define LEDColorWhite2() LED2Color_t( 0, 0, 0, 255) +#else + #define LEDColorWhite2() LED2Color_t(255, 255, 255) +#endif + + class LEDLights { public: + #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED) + static LED1Color_t color; // last non-off color + static bool lights_on; // the last set color was "on" + #else + static constexpr bool lights_on = true; + #endif + LEDLights() {} // ctor static void setup(); // init() - static void set_color(const LEDColor &color + static void set_color(const LED1Color_t &color OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ); @@ -120,7 +201,7 @@ public: OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ) { - set_color(LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, i)) OPTARG(NEOPIXEL_IS_SEQUENTIAL, isSequence)); + set_color(LED1Color_t(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, i)) OPTARG(NEOPIXEL_IS_SEQUENTIAL, isSequence)); } static void set_off() { set_color(LEDColorOff()); } @@ -128,7 +209,7 @@ public: static void set_white() { set_color(LEDColorWhite()); } #if ENABLED(LED_COLOR_PRESETS) - static const LEDColor defaultLEDColor; + static const LED1Color_t defaultLEDColor; static void set_default() { set_color(defaultLEDColor); } static void set_red() { set_color(LEDColorRed()); } static void set_orange() { set_color(LEDColorOrange()); } @@ -139,22 +220,17 @@ public: #endif #if ENABLED(PRINTER_EVENT_LEDS) - static LEDColor get_color() { return lights_on ? color : LEDColorOff(); } - #endif - - #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED) - static LEDColor color; // last non-off color - static bool lights_on; // the last set color was "on" + static LED1Color_t get_color() { return lights_on ? color : LEDColorOff(); } #endif #if ENABLED(LED_CONTROL_MENU) static void toggle(); // swap "off" with color #endif - #if EITHER(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) + #if ANY(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED, HAS_LED_POWEROFF_TIMEOUT) static void update() { set_color(color); } #endif - #if LED_POWEROFF_TIMEOUT > 0 + #if HAS_LED_POWEROFF_TIMEOUT private: static millis_t led_off_time; public: @@ -176,35 +252,35 @@ extern LEDLights leds; static void setup(); // init() - static void set_color(const LEDColor &color); + static void set_color(const LED2Color_t &color); static void set_color(uint8_t r, uint8_t g, uint8_t b - OPTARG(HAS_WHITE_LED, uint8_t w=0) + OPTARG(HAS_WHITE_LED2, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) ) { - set_color(LEDColor(r, g, b - OPTARG(HAS_WHITE_LED, w) + set_color(LED2Color_t(r, g, b + OPTARG(HAS_WHITE_LED2, w) OPTARG(NEOPIXEL_LED, i) )); } - static void set_off() { set_color(LEDColorOff()); } - static void set_green() { set_color(LEDColorGreen()); } - static void set_white() { set_color(LEDColorWhite()); } + static void set_off() { set_color(LEDColorOff2()); } + static void set_green() { set_color(LEDColorGreen2()); } + static void set_white() { set_color(LEDColorWhite2()); } #if ENABLED(NEO2_COLOR_PRESETS) - static const LEDColor defaultLEDColor; - static void set_default() { set_color(defaultLEDColor); } - static void set_red() { set_color(LEDColorRed()); } - static void set_orange() { set_color(LEDColorOrange()); } - static void set_yellow() { set_color(LEDColorYellow()); } - static void set_blue() { set_color(LEDColorBlue()); } - static void set_indigo() { set_color(LEDColorIndigo()); } - static void set_violet() { set_color(LEDColorViolet()); } + static const LED2Color_t defaultLEDColor2; + static void set_default() { set_color(defaultLEDColor2); } + static void set_red() { set_color(LEDColorRed2()); } + static void set_orange() { set_color(LEDColorOrange2()); } + static void set_yellow() { set_color(LEDColorYellow2()); } + static void set_blue() { set_color(LEDColorBlue2()); } + static void set_indigo() { set_color(LEDColorIndigo2()); } + static void set_violet() { set_color(LEDColorViolet2()); } #endif #if ENABLED(NEOPIXEL2_SEPARATE) - static LEDColor color; // last non-off color + static LED2Color_t color; // last non-off color static bool lights_on; // the last set color was "on" static void toggle(); // swap "off" with color static void update() { set_color(color); } diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp index 4f104234f1..8165c7715c 100644 --- a/Marlin/src/feature/leds/neopixel.cpp +++ b/Marlin/src/feature/leds/neopixel.cpp @@ -30,7 +30,7 @@ #include "leds.h" -#if EITHER(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) +#if ANY(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) #include "../../core/utility.h" #endif @@ -54,7 +54,15 @@ Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIX set_background_color(background_color); } -#endif + void Marlin_NeoPixel::set_background_off() { + #ifndef NEOPIXEL_BKGD_TIMEOUT_COLOR + #define NEOPIXEL_BKGD_TIMEOUT_COLOR { 0, 0, 0, 0 } + #endif + constexpr uint8_t background_color_off[4] = NEOPIXEL_BKGD_TIMEOUT_COLOR; + set_background_color(background_color_off); + } + +#endif // NEOPIXEL_BKGD_INDEX_FIRST void Marlin_NeoPixel::set_color(const uint32_t color) { if (neoindex >= 0) { @@ -95,7 +103,7 @@ void Marlin_NeoPixel::init() { safe_delay(500); set_color_startup(adaneo1.Color(0, 0, 255, 0)); // blue safe_delay(500); - #if HAS_WHITE_LED + #if HAS_WHITE_NEOPIXEL_1 set_color_startup(adaneo1.Color(0, 0, 0, 255)); // white safe_delay(500); #endif @@ -108,7 +116,7 @@ void Marlin_NeoPixel::init() { set_color(adaneo1.Color TERN(LED_USER_PRESET_STARTUP, (LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, LED_USER_PRESET_WHITE), - (255, 255, 255, 255)) + (0, 0, 0, 0)) ); } @@ -150,7 +158,7 @@ void Marlin_NeoPixel::init() { safe_delay(500); set_color_startup(adaneo.Color(0, 0, 255, 0)); // blue safe_delay(500); - #if HAS_WHITE_LED2 + #if HAS_WHITE_NEOPIXEL_2 set_color_startup(adaneo.Color(0, 0, 0, 255)); // white safe_delay(500); #endif diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index 2048e2c2ee..f420a25b83 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -42,31 +42,31 @@ // Defines // ------------------------ -#define _NEO_IS_RGB(N) (N == NEO_RGB || N == NEO_RBG || N == NEO_GRB || N == NEO_GBR || N == NEO_BRG || N == NEO_BGR) +#define _NEO_IS_RGBW(N) ((N) & 0x30) != (((N) >> 2) & 0x30) -#if !_NEO_IS_RGB(NEOPIXEL_TYPE) - #define HAS_WHITE_LED 1 +#if _NEO_IS_RGBW(NEOPIXEL_TYPE) + #define HAS_WHITE_NEOPIXEL_1 1 #endif -#if HAS_WHITE_LED - #define NEO_WHITE 0, 0, 0, 255 -#else - #define NEO_WHITE 255, 255, 255 -#endif - -#if defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE && DISABLED(NEOPIXEL2_SEPARATE) +#if ENABLED(NEOPIXEL2_SEPARATE) + #if _NEO_IS_RGBW(NEOPIXEL2_TYPE) + #define HAS_WHITE_NEOPIXEL_2 1 + #endif +#elif defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE #define MULTIPLE_NEOPIXEL_TYPES 1 #endif -#if EITHER(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) +#if ANY(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) #define CONJOINED_NEOPIXEL 1 #endif +#undef _NEO_IS_RGBW + // ------------------------ // Types // ------------------------ -typedef IF<(TERN0(NEOPIXEL_LED, NEOPIXEL_PIXELS > 127)), int16_t, int8_t>::type pixel_index_t; +typedef value_t(TERN0(NEOPIXEL_LED, NEOPIXEL_PIXELS)) pixel_index_t; // ------------------------ // Classes @@ -91,6 +91,7 @@ public: static void set_background_color(const uint8_t r, const uint8_t g, const uint8_t b, const uint8_t w); static void set_background_color(const uint8_t (&rgbw)[4]) { set_background_color(rgbw[0], rgbw[1], rgbw[2], rgbw[3]); } static void reset_background_color(); + static void set_background_off(); #endif static void begin() { @@ -129,7 +130,7 @@ public: } // Accessors - static uint16_t pixels() { return adaneo1.numPixels() * TERN1(NEOPIXEL2_INSERIES, 2); } + static uint16_t pixels() { return MUL_TERN(NEOPIXEL2_INSERIES, adaneo1.numPixels(), 2); } static uint32_t pixel_color(const uint16_t n) { #if ENABLED(NEOPIXEL2_INSERIES) @@ -140,8 +141,17 @@ public: static uint8_t brightness() { return adaneo1.getBrightness(); } - static uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w)) { - return adaneo1.Color(r, g, b OPTARG(HAS_WHITE_LED, w)); + static uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_NEOPIXEL_1, uint8_t w=0)) { + return adaneo1.Color(r, g, b OPTARG(HAS_WHITE_NEOPIXEL_1, w)); + } + static uint32_t White() { + return Color( + #if HAS_WHITE_NEOPIXEL_1 + 0, 0, 0, 255 + #else + 255, 255, 255 + #endif + ); } }; @@ -150,15 +160,6 @@ extern Marlin_NeoPixel neo; // Neo pixel channel 2 #if ENABLED(NEOPIXEL2_SEPARATE) - #if _NEO_IS_RGB(NEOPIXEL2_TYPE) - #define NEOPIXEL2_IS_RGB 1 - #define NEO2_WHITE 255, 255, 255 - #else - #define NEOPIXEL2_IS_RGBW 1 - #define HAS_WHITE_LED2 1 // A white component can be passed for NEOPIXEL2 - #define NEO2_WHITE 0, 0, 0, 255 - #endif - class Marlin_NeoPixel2 { private: static Adafruit_NeoPixel adaneo; @@ -183,13 +184,20 @@ extern Marlin_NeoPixel neo; static uint16_t pixels() { return adaneo.numPixels();} static uint32_t pixel_color(const uint16_t n) { return adaneo.getPixelColor(n); } static uint8_t brightness() { return adaneo.getBrightness(); } - static uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED2, uint8_t w)) { - return adaneo.Color(r, g, b OPTARG(HAS_WHITE_LED2, w)); + static uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_NEOPIXEL_2, uint8_t w=0)) { + return adaneo.Color(r, g, b OPTARG(HAS_WHITE_NEOPIXEL_2, w)); + } + static uint32_t White() { + return Color( + #if HAS_WHITE_NEOPIXEL_2 + 0, 0, 0, 255 + #else + 255, 255, 255 + #endif + ); } }; extern Marlin_NeoPixel2 neo2; #endif // NEOPIXEL2_SEPARATE - -#undef _NEO_IS_RGB diff --git a/Marlin/src/feature/leds/pca9533.cpp b/Marlin/src/feature/leds/pca9533.cpp index 914db21ba3..d71760e2cb 100644 --- a/Marlin/src/feature/leds/pca9533.cpp +++ b/Marlin/src/feature/leds/pca9533.cpp @@ -1,4 +1,4 @@ -/* +/** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * diff --git a/Marlin/src/feature/leds/pca9533.h b/Marlin/src/feature/leds/pca9533.h index 431058c491..3a18e96b24 100644 --- a/Marlin/src/feature/leds/pca9533.h +++ b/Marlin/src/feature/leds/pca9533.h @@ -1,4 +1,4 @@ -/* +/** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * @@ -21,7 +21,7 @@ */ #pragma once -/* +/** * Driver for the PCA9533 LED controller found on the MightyBoard * used by FlashForge Creator Pro, MakerBot, etc. * Written 2020 APR 01 by grauerfuchs diff --git a/Marlin/src/feature/leds/pca9632.cpp b/Marlin/src/feature/leds/pca9632.cpp index abea988004..d8fba380a4 100644 --- a/Marlin/src/feature/leds/pca9632.cpp +++ b/Marlin/src/feature/leds/pca9632.cpp @@ -68,7 +68,7 @@ #ifndef PCA9632_BLU #define PCA9632_BLU 0x04 #endif -#if HAS_WHITE_LED && !defined(PCA9632_WHT) +#if ENABLED(PCA9632_RGBW) && !defined(PCA9632_WHT) #define PCA9632_WHT 0x06 #endif @@ -124,7 +124,7 @@ static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const } #endif -void PCA9632_set_led_color(const LEDColor &color) { +void PCA9632_set_led_color(const LED1Color_t &color) { Wire.begin(); if (!PCA_init) { PCA_init = 1; @@ -135,10 +135,7 @@ void PCA9632_set_led_color(const LEDColor &color) { const byte LEDOUT = (color.r ? LED_PWM << PCA9632_RED : 0) | (color.g ? LED_PWM << PCA9632_GRN : 0) | (color.b ? LED_PWM << PCA9632_BLU : 0) - #if ENABLED(PCA9632_RGBW) - | (color.w ? LED_PWM << PCA9632_WHT : 0) - #endif - ; + | (TERN0(PCA9632_RGBW, color.w ? LED_PWM << PCA9632_WHT : 0)); PCA9632_WriteAllRegisters(PCA9632_ADDRESS,PCA9632_PWM0, color.r, color.g, color.b OPTARG(PCA9632_RGBW, color.w) @@ -148,7 +145,7 @@ void PCA9632_set_led_color(const LEDColor &color) { #if ENABLED(PCA9632_BUZZER) - void PCA9632_buzz(const long, const uint16_t) { + void PCA9632_buzz(const long, const uint16_t/*=0*/) { uint8_t data[] = PCA9632_BUZZER_DATA; Wire.beginTransmission(I2C_ADDRESS(PCA9632_ADDRESS)); Wire.write(data, sizeof(data)); diff --git a/Marlin/src/feature/leds/pca9632.h b/Marlin/src/feature/leds/pca9632.h index fb59a8c184..442166c245 100644 --- a/Marlin/src/feature/leds/pca9632.h +++ b/Marlin/src/feature/leds/pca9632.h @@ -26,12 +26,11 @@ * Written by Robert Mendon Feb 2017. */ -struct LEDColor; -typedef LEDColor LEDColor; +struct LED1Color_t; -void PCA9632_set_led_color(const LEDColor &color); +void PCA9632_set_led_color(const LED1Color_t &color); #if ENABLED(PCA9632_BUZZER) #include - void PCA9632_buzz(const long, const uint16_t); + void PCA9632_buzz(const long, const uint16_t=0); #endif diff --git a/Marlin/src/feature/leds/printer_event_leds.cpp b/Marlin/src/feature/leds/printer_event_leds.cpp index e6407a6320..3cbce3da8c 100644 --- a/Marlin/src/feature/leds/printer_event_leds.cpp +++ b/Marlin/src/feature/leds/printer_event_leds.cpp @@ -47,7 +47,7 @@ PrinterEventLEDs printerEventLEDs; inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b OPTARG(HAS_WHITE_LED, const uint8_t w=0)) { leds.set_color( - LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, neo.brightness())) + LED1Color_t(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, neo.brightness())) OPTARG(NEOPIXEL_IS_SEQUENTIAL, true) ); } diff --git a/Marlin/src/feature/leds/printer_event_leds.h b/Marlin/src/feature/leds/printer_event_leds.h index 2a4342e8f5..5fb08a547e 100644 --- a/Marlin/src/feature/leds/printer_event_leds.h +++ b/Marlin/src/feature/leds/printer_event_leds.h @@ -40,26 +40,26 @@ private: public: #if HAS_TEMP_HOTEND - static LEDColor onHotendHeatingStart() { old_intensity = 0; return leds.get_color(); } + static LED1Color_t onHotendHeatingStart() { old_intensity = 0; return leds.get_color(); } static void onHotendHeating(const celsius_t start, const celsius_t current, const celsius_t target); #endif #if HAS_HEATED_BED - static LEDColor onBedHeatingStart() { old_intensity = 127; return leds.get_color(); } + static LED1Color_t onBedHeatingStart() { old_intensity = 127; return leds.get_color(); } static void onBedHeating(const celsius_t start, const celsius_t current, const celsius_t target); #endif #if HAS_HEATED_CHAMBER - static LEDColor onChamberHeatingStart() { old_intensity = 127; return leds.get_color(); } + static LED1Color_t onChamberHeatingStart() { old_intensity = 127; return leds.get_color(); } static void onChamberHeating(const celsius_t start, const celsius_t current, const celsius_t target); #endif #if HAS_TEMP_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER static void onHeatingDone() { leds.set_white(); } - static void onPidTuningDone(LEDColor c) { leds.set_color(c); } + static void onPIDTuningDone(LED1Color_t c) { leds.set_color(c); } #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static void onPrintCompleted() { leds.set_green(); @@ -80,7 +80,7 @@ public: #endif } - #endif // SDSUPPORT + #endif // HAS_MEDIA }; extern PrinterEventLEDs printerEventLEDs; diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index 2fdfcba32d..81f588008d 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -39,11 +39,12 @@ #if ENABLED(MAX7219_DEBUG) -#define MAX7219_ERRORS // Disable to save 406 bytes of Program Memory +#define MAX7219_ERRORS // Requires ~400 bytes of flash #include "max7219.h" #include "../module/planner.h" +#include "../module/stepper.h" #include "../MarlinCore.h" #include "../HAL/shared/Delay.h" @@ -71,6 +72,26 @@ uint16_t CodeProfiler::call_count = 0; #endif +#if defined(MAX7219_DEBUG_PLANNER_HEAD) && defined(MAX7219_DEBUG_PLANNER_TAIL) && MAX7219_DEBUG_PLANNER_HEAD == MAX7219_DEBUG_PLANNER_TAIL + static int16_t last_head_cnt = 0xF, last_tail_cnt = 0xF; +#else + #ifdef MAX7219_DEBUG_PLANNER_HEAD + static int16_t last_head_cnt = 0x1; + #endif + #ifdef MAX7219_DEBUG_PLANNER_TAIL + static int16_t last_tail_cnt = 0x1; + #endif +#endif +#ifdef MAX7219_DEBUG_PLANNER_QUEUE + static int16_t last_depth = 0; +#endif +#ifdef MAX7219_DEBUG_PROFILE + static uint8_t last_time_fraction = 0; +#endif +#ifdef MAX7219_DEBUG_MULTISTEPPING + static uint8_t last_multistepping = 0; +#endif + Max7219 max7219; uint8_t Max7219::led_line[MAX7219_LINES]; // = { 0 }; @@ -135,9 +156,7 @@ uint8_t Max7219::suspended; // = 0; void Max7219::error(FSTR_P const func, const int32_t v1, const int32_t v2/*=-1*/) { #if ENABLED(MAX7219_ERRORS) - SERIAL_ECHOPGM("??? Max7219::"); - SERIAL_ECHOF(func, AS_CHAR('(')); - SERIAL_ECHO(v1); + SERIAL_ECHO(F("??? Max7219::"), func, C('('), v1); if (v2 > 0) SERIAL_ECHOPGM(", ", v2); SERIAL_CHAR(')'); SERIAL_EOL(); @@ -155,7 +174,7 @@ void Max7219::error(FSTR_P const func, const int32_t v1, const int32_t v2/*=-1*/ */ inline uint32_t flipped(const uint32_t bits, const uint8_t n_bytes) { uint32_t mask = 1, outbits = 0; - LOOP_L_N(b, n_bytes * 8) { + for (uint8_t b = 0; b < n_bytes * 8; ++b) { outbits <<= 1; if (bits & mask) outbits |= 1; mask <<= 1; @@ -264,7 +283,7 @@ void Max7219::set(const uint8_t line, const uint8_t bits) { } // Draw a float with a decimal point and optional digits - void Max7219::print(const uint8_t start, const_float_t value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false) { + void Max7219::print(const uint8_t start, const float value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false) { if (pre_size) print(start, value, pre_size, leadzero, !!post_size); if (post_size) { const int16_t after = ABS(value) * (10 ^ post_size); @@ -338,13 +357,13 @@ void Max7219::fill() { void Max7219::clear_row(const uint8_t row) { if (row >= MAX7219_Y_LEDS) return error(F("clear_row"), row); - LOOP_L_N(x, MAX7219_X_LEDS) CLR_7219(x, row); + for (uint8_t x = 0; x < MAX7219_X_LEDS; ++x) CLR_7219(x, row); send_row(row); } void Max7219::clear_column(const uint8_t col) { if (col >= MAX7219_X_LEDS) return error(F("set_column"), col); - LOOP_L_N(y, MAX7219_Y_LEDS) CLR_7219(col, y); + for (uint8_t y = 0; y < MAX7219_Y_LEDS; ++y) CLR_7219(col, y); send_column(col); } @@ -356,7 +375,7 @@ void Max7219::clear_column(const uint8_t col) { void Max7219::set_row(const uint8_t row, const uint32_t val) { if (row >= MAX7219_Y_LEDS) return error(F("set_row"), row); uint32_t mask = _BV32(MAX7219_X_LEDS - 1); - LOOP_L_N(x, MAX7219_X_LEDS) { + for (uint8_t x = 0; x < MAX7219_X_LEDS; ++x) { if (val & mask) SET_7219(x, row); else CLR_7219(x, row); mask >>= 1; } @@ -371,7 +390,7 @@ void Max7219::set_row(const uint8_t row, const uint32_t val) { void Max7219::set_column(const uint8_t col, const uint32_t val) { if (col >= MAX7219_X_LEDS) return error(F("set_column"), col); uint32_t mask = _BV32(MAX7219_Y_LEDS - 1); - LOOP_L_N(y, MAX7219_Y_LEDS) { + for (uint8_t y = 0; y < MAX7219_Y_LEDS; ++y) { if (val & mask) SET_7219(col, y); else CLR_7219(col, y); mask >>= 1; } @@ -436,23 +455,23 @@ void Max7219::set_columns_32bits(const uint8_t x, uint32_t val) { // Initialize the Max7219 void Max7219::register_setup() { - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_scanLimit, 0x07); pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_decodeMode, 0x00); // Using an led matrix (not digits) pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_shutdown, 0x01); // Not in shutdown mode pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_displayTest, 0x00); // No display test pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_intensity, 0x01 & 0x0F); // The first 0x0F is the value you can set // Range: 0x00 to 0x0F pulse_load(); // Tell the chips to load the clocked out data @@ -461,32 +480,30 @@ void Max7219::register_setup() { #if MAX7219_INIT_TEST uint8_t test_mode = 0; - millis_t next_patt_ms; bool patt_on; #if MAX7219_INIT_TEST == 2 #define MAX7219_LEDS (MAX7219_X_LEDS * MAX7219_Y_LEDS) - constexpr millis_t pattern_delay = 4; + xy_int8_t spiral; + int8_t spiral_dir; + uvalue_t(MAX7219_LEDS) spiral_count; - int8_t spiralx, spiraly, spiral_dir; - IF<(MAX7219_LEDS > 255), uint16_t, uint8_t>::type spiral_count; - - void Max7219::test_pattern() { - constexpr int8_t way[][2] = { { 1, 0 }, { 0, 1 }, { -1, 0 }, { 0, -1 } }; - led_set(spiralx, spiraly, patt_on); - const int8_t x = spiralx + way[spiral_dir][0], y = spiraly + way[spiral_dir][1]; - if (!WITHIN(x, 0, MAX7219_X_LEDS - 1) || !WITHIN(y, 0, MAX7219_Y_LEDS - 1) || BIT_7219(x, y) == patt_on) + void Max7219::run_test_pattern() { + constexpr xy_int8_t way[] = { { 1, 0 }, { 0, 1 }, { -1, 0 }, { 0, -1 } }; + led_set(spiral.x, spiral.y, patt_on); + const xy_int8_t xy = spiral + way[spiral_dir]; + if (!WITHIN(xy.x, 0, MAX7219_X_LEDS - 1) || !WITHIN(xy.y, 0, MAX7219_Y_LEDS - 1) || BIT_7219(xy.x, xy.y) == patt_on) spiral_dir = (spiral_dir + 1) & 0x3; - spiralx += way[spiral_dir][0]; - spiraly += way[spiral_dir][1]; + spiral += way[spiral_dir]; if (!spiral_count--) { if (!patt_on) test_mode = 0; else { spiral_count = MAX7219_LEDS; - spiralx = spiraly = spiral_dir = 0; + spiral.reset(); + spiral_dir = 0; patt_on = false; } } @@ -497,7 +514,11 @@ void Max7219::register_setup() { constexpr millis_t pattern_delay = 20; int8_t sweep_count, sweepx, sweep_dir; - void Max7219::test_pattern() { + void Max7219::run_test_pattern() { + static millis_t next_pattern_ms = 0; + const millis_t ms = millis(); + if (PENDING(ms, next_pattern_ms)) return; + next_pattern_ms = ms + pattern_delay; set_column(sweepx, patt_on ? 0xFFFFFFFF : 0x00000000); sweepx += sweep_dir; if (!WITHIN(sweepx, 0, MAX7219_X_LEDS - 1)) { @@ -507,27 +528,21 @@ void Max7219::register_setup() { } else sweepx -= MAX7219_X_LEDS * sweep_dir; - patt_on ^= true; - next_patt_ms += 100; + FLIP(patt_on); + next_pattern_ms += 100; if (++test_mode > 4) test_mode = 0; } } #endif - void Max7219::run_test_pattern() { - const millis_t ms = millis(); - if (PENDING(ms, next_patt_ms)) return; - next_patt_ms = ms + pattern_delay; - test_pattern(); - } - void Max7219::start_test_pattern() { clear(); test_mode = 1; patt_on = true; #if MAX7219_INIT_TEST == 2 - spiralx = spiraly = spiral_dir = 0; + spiral.reset(); + spiral_dir = 0; spiral_count = MAX7219_LEDS; #else sweep_dir = 1; @@ -551,6 +566,29 @@ void Max7219::init() { #if MAX7219_INIT_TEST start_test_pattern(); #endif + + #ifdef MAX7219_REINIT_ON_POWERUP + #if defined(MAX7219_DEBUG_PLANNER_HEAD) && defined(MAX7219_DEBUG_PLANNER_TAIL) && MAX7219_DEBUG_PLANNER_HEAD == MAX7219_DEBUG_PLANNER_TAIL + last_head_cnt = 0xF; + last_tail_cnt = 0xF; + #else + #ifdef MAX7219_DEBUG_PLANNER_HEAD + last_head_cnt = 0x1; + #endif + #ifdef MAX7219_DEBUG_PLANNER_TAIL + last_tail_cnt = 0x1; + #endif + #endif + #ifdef MAX7219_DEBUG_PLANNER_QUEUE + last_depth = 0; + #endif + #ifdef MAX7219_DEBUG_PROFILE + last_time_fraction = 0; + #endif + #ifdef MAX7219_DEBUG_MULTISTEPPING + last_multistepping = 0; + #endif + #endif } /** @@ -677,8 +715,6 @@ void Max7219::idle_tasks() { #if defined(MAX7219_DEBUG_PLANNER_HEAD) && defined(MAX7219_DEBUG_PLANNER_TAIL) && MAX7219_DEBUG_PLANNER_HEAD == MAX7219_DEBUG_PLANNER_TAIL - 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, &row_change_mask); last_head_cnt = head; @@ -688,7 +724,6 @@ void Max7219::idle_tasks() { #else #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, &row_change_mask); last_head_cnt = head; @@ -696,7 +731,6 @@ void Max7219::idle_tasks() { #endif #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, &row_change_mask); last_tail_cnt = tail; @@ -706,8 +740,7 @@ void Max7219::idle_tasks() { #endif #ifdef MAX7219_DEBUG_PLANNER_QUEUE - static int16_t last_depth = 0; - const int16_t current_depth = (head - tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1) & 0xF; + const int16_t current_depth = BLOCK_MOD(head - tail + (BLOCK_BUFFER_SIZE)) & 0xF; if (current_depth != last_depth) { quantity16(MAX7219_DEBUG_PLANNER_QUEUE, last_depth, current_depth, &row_change_mask); last_depth = current_depth; @@ -715,7 +748,6 @@ void Max7219::idle_tasks() { #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); @@ -723,10 +755,32 @@ void Max7219::idle_tasks() { } #endif + #ifdef MAX7219_DEBUG_MULTISTEPPING + static uint8_t last_multistepping = 0; + const uint8_t multistepping = stepper.steps_per_isr; + if (multistepping != last_multistepping) { + static uint8_t log2_old = 0; + uint8_t log2_new = 0; + for (uint8_t val = multistepping; val > 1; val >>= 1) log2_new++; + mark16(MAX7219_DEBUG_MULTISTEPPING, log2_old, log2_new, &row_change_mask); + last_multistepping = multistepping; + log2_old = log2_new; + } + #endif + + #ifdef MAX7219_DEBUG_SLOWDOWN + static uint8_t last_slowdown_count = 0; + const uint8_t slowdown_count = planner.slowdown_count; + if (slowdown_count != last_slowdown_count) { + mark16(MAX7219_DEBUG_SLOWDOWN, last_slowdown_count, slowdown_count, &row_change_mask); + last_slowdown_count = slowdown_count; + } + #endif + // batch line updates suspended--; if (!suspended) - LOOP_L_N(i, 8) if (row_change_mask & _BV(i)) + for (uint8_t i = 0; i < 8; ++i) if (row_change_mask & _BV(i)) refresh_line(i); // After resume() automatically do a refresh() diff --git a/Marlin/src/feature/max7219.h b/Marlin/src/feature/max7219.h index a6b110fdf4..9c39541a7c 100644 --- a/Marlin/src/feature/max7219.h +++ b/Marlin/src/feature/max7219.h @@ -74,14 +74,13 @@ #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. + // By default there is one instantiated for the duration of marlin.idle() + // but an instance can be created in any code block to measure time spent + // from instantiation until the CPU leaves the 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 }; @@ -110,7 +109,7 @@ if (mode == ACCUMULATE_TOTAL) return; // update time_fraction every hundred milliseconds - if (instance_count == 0 && ELAPSED(now, last_calc_time + 100000)) { + if (instance_count == 0 && now - last_calc_time > 100000) { time_fraction = total_time * 128 / (now - last_calc_time); last_calc_time = now; total_time = 0; @@ -166,7 +165,7 @@ public: // Draw an integer with optional leading zeros and optional decimal point void print(const uint8_t start, int16_t value, uint8_t size, const bool leadzero=false, bool dec=false); // Draw a float with a decimal point and optional digits - void print(const uint8_t start, const_float_t value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false); + void print(const uint8_t start, const float value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false); #endif // Set a single LED by XY coordinate diff --git a/Marlin/src/feature/meatpack.cpp b/Marlin/src/feature/meatpack.cpp index 07ff41e5be..3b762d4ded 100644 --- a/Marlin/src/feature/meatpack.cpp +++ b/Marlin/src/feature/meatpack.cpp @@ -140,7 +140,7 @@ void MeatPack::handle_output_char(const uint8_t c) { #if ENABLED(MP_DEBUG) if (chars_decoded < 1024) { ++chars_decoded; - DEBUG_ECHOLNPGM("RB: ", AS_CHAR(c)); + DEBUG_ECHOLNPGM("RB: ", C(c)); } #endif } @@ -169,9 +169,11 @@ void MeatPack::handle_command(const MeatPack_Command c) { void MeatPack::report_state() { // NOTE: if any configuration vars are added below, the outgoing sync text for host plugin // should not contain the "PV' substring, as this is used to indicate protocol version - SERIAL_ECHOPGM("[MP] " MeatPack_ProtocolVersion " "); - serialprint_onoff(TEST(state, MPConfig_Bit_Active)); - SERIAL_ECHOF(TEST(state, MPConfig_Bit_NoSpaces) ? F(" NSP\n") : F(" ESP\n")); + SERIAL_ECHO( + F("[MP] " MeatPack_ProtocolVersion " "), + ON_OFF(TEST(state, MPConfig_Bit_Active)), + TEST(state, MPConfig_Bit_NoSpaces) ? F(" NSP\n") : F(" ESP\n") + ); } /** diff --git a/Marlin/src/feature/meatpack.h b/Marlin/src/feature/meatpack.h index 98a535e592..0de1f792c1 100644 --- a/Marlin/src/feature/meatpack.h +++ b/Marlin/src/feature/meatpack.h @@ -20,7 +20,7 @@ * */ -/* +/** * MeatPack G-code Compression * * Algorithm & Implementation: Scott Mudge - mail@scottmudge.com @@ -144,7 +144,6 @@ struct MeatpackSerial : public SerialBase > { void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); } SerialFeature features(serial_index_t index) const { return SerialFeature::MeatPack | CALL_IF_EXISTS(SerialFeature, &out, features, index); } - int available(serial_index_t index) { if (charCount) return charCount; // The buffer still has data if (out.available(index) <= 0) return 0; // No data to read diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index b1a069e320..bc98bf3b26 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -24,16 +24,10 @@ #if ENABLED(MIXING_EXTRUDER) -//#define MIXER_NORMALIZER_DEBUG - #include "mixing.h" Mixer mixer; -#ifdef MIXER_NORMALIZER_DEBUG - #include "../core/serial.h" -#endif - // Used up to Planner level uint_fast8_t Mixer::selected_vtool = 0; float Mixer::collector[MIXING_STEPPERS]; // mix proportion. 0.0 = off, otherwise <= COLOR_A_MASK. @@ -44,7 +38,7 @@ int_fast8_t Mixer::runner = 0; mixer_comp_t Mixer::s_color[MIXING_STEPPERS]; mixer_accu_t Mixer::accu[MIXING_STEPPERS] = { 0 }; -#if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) +#if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) mixer_perc_t Mixer::mix[MIXING_STEPPERS]; #endif @@ -62,10 +56,7 @@ void Mixer::normalize(const uint8_t tool_index) { } #ifdef MIXER_NORMALIZER_DEBUG SERIAL_ECHOPGM("Mixer: Old relation : [ "); - MIXER_STEPPER_LOOP(i) { - SERIAL_DECIMAL(collector[i] / csum); - SERIAL_CHAR(' '); - } + MIXER_STEPPER_LOOP(i) SERIAL_ECHO(collector[i] / csum, C(' ')); SERIAL_ECHOLNPGM("]"); #endif @@ -77,16 +68,12 @@ void Mixer::normalize(const uint8_t tool_index) { csum = 0; SERIAL_ECHOPGM("Mixer: Normalize to : [ "); MIXER_STEPPER_LOOP(i) { - SERIAL_ECHO(uint16_t(color[tool_index][i])); - SERIAL_CHAR(' '); + SERIAL_ECHO(uint16_t(color[tool_index][i]), C(' ')); csum += color[tool_index][i]; } SERIAL_ECHOLNPGM("]"); SERIAL_ECHOPGM("Mixer: New relation : [ "); - MIXER_STEPPER_LOOP(i) { - SERIAL_ECHO_F(uint16_t(color[tool_index][i]) / csum, 3); - SERIAL_CHAR(' '); - } + MIXER_STEPPER_LOOP(i) SERIAL_ECHO(p_float_t(uint16_t(color[tool_index][i]) / csum, 3), C(' ')); SERIAL_ECHOLNPGM("]"); #endif @@ -96,13 +83,13 @@ void Mixer::normalize(const uint8_t tool_index) { void Mixer::reset_vtools() { // Virtual Tools 0, 1, 2, 3 = Filament 1, 2, 3, 4, etc. // Every virtual tool gets a pure filament - LOOP_L_N(t, _MIN(MIXING_VIRTUAL_TOOLS, MIXING_STEPPERS)) + for (uint8_t t = 0; t < _MIN(MIXING_VIRTUAL_TOOLS, MIXING_STEPPERS); ++t) MIXER_STEPPER_LOOP(i) color[t][i] = (t == i) ? COLOR_A_MASK : 0; // Remaining virtual tools are 100% filament 1 #if MIXING_VIRTUAL_TOOLS > MIXING_STEPPERS - LOOP_S_L_N(t, MIXING_STEPPERS, MIXING_VIRTUAL_TOOLS) + for (uint8_t t = MIXING_STEPPERS; t < MIXING_VIRTUAL_TOOLS; ++t) MIXER_STEPPER_LOOP(i) color[t][i] = (i == 0) ? COLOR_A_MASK : 0; #endif @@ -140,7 +127,7 @@ void Mixer::init() { color[MIXER_AUTORETRACT_TOOL][i] = COLOR_A_MASK; #endif - #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) + #if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) update_mix_from_vtool(); #endif @@ -179,7 +166,7 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*= float Mixer::prev_z; // = 0 - void Mixer::update_gradient_for_z(const_float_t z) { + void Mixer::update_gradient_for_z(const float z) { if (z == prev_z) return; prev_z = z; diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index 85d52d69c8..bd7ffb560e 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -43,10 +43,6 @@ typedef int8_t mixer_perc_t; -#ifndef MIXING_VIRTUAL_TOOLS - #define MIXING_VIRTUAL_TOOLS 1 -#endif - enum MixTool { FIRST_USER_VIRTUAL_TOOL = 0 , LAST_USER_VIRTUAL_TOOL = MIXING_VIRTUAL_TOOLS - 1 @@ -108,7 +104,7 @@ class Mixer { } // Used when dealing with blocks - FORCE_INLINE static void populate_block(mixer_comp_t b_color[MIXING_STEPPERS]) { + FORCE_INLINE static void populate_block(mixer_comp_t (&b_color)[MIXING_STEPPERS]) { #if ENABLED(GRADIENT_MIX) if (gradient.enabled) { MIXER_STEPPER_LOOP(i) b_color[i] = gradient.color[i]; @@ -118,11 +114,11 @@ class Mixer { MIXER_STEPPER_LOOP(i) b_color[i] = color[selected_vtool][i]; } - FORCE_INLINE static void stepper_setup(mixer_comp_t b_color[MIXING_STEPPERS]) { + FORCE_INLINE static void stepper_setup(mixer_comp_t (&b_color)[MIXING_STEPPERS]) { MIXER_STEPPER_LOOP(i) s_color[i] = b_color[i]; } - #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) + #if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) static mixer_perc_t mix[MIXING_STEPPERS]; // Scratch array for the Mix in proportion to 100 @@ -137,26 +133,24 @@ class Mixer { MIXER_STEPPER_LOOP(i) tcolor[i] = mix[i] * scale; #ifdef MIXER_NORMALIZER_DEBUG - SERIAL_ECHOPGM("Mix [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]); - SERIAL_ECHOPGM(" ] to Color [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, tcolor[0], tcolor[1], tcolor[2], tcolor[3], tcolor[4], tcolor[5]); - SERIAL_ECHOLNPGM(" ]"); + SERIAL_ECHOLN( + F("Mix [ "), LIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]), + F(" ] to Color [ "), LIST_N(MIXING_STEPPERS, tcolor[0], tcolor[1], tcolor[2], tcolor[3], tcolor[4], tcolor[5]), + F(" ]") + ); #endif } static void update_mix_from_vtool(const uint8_t j=selected_vtool) { float ctot = 0; MIXER_STEPPER_LOOP(i) ctot += color[j][i]; - //MIXER_STEPPER_LOOP(i) mix[i] = 100.0f * color[j][i] / ctot; - MIXER_STEPPER_LOOP(i) mix[i] = mixer_perc_t(100.0f * color[j][i] / ctot); + MIXER_STEPPER_LOOP(i) mix[i] = mixer_perc_t(100.0f * color[j][i] / ctot + 0.5f); #ifdef MIXER_NORMALIZER_DEBUG - SERIAL_ECHOPGM("V-tool ", j, " [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, color[j][0], color[j][1], color[j][2], color[j][3], color[j][4], color[j][5]); - SERIAL_ECHOPGM(" ] to Mix [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]); - SERIAL_ECHOLNPGM(" ]"); + SERIAL_ECHOLN(F("V-tool "), j, + F(" [ "), LIST_N(MIXING_STEPPERS, color[j][0], color[j][1], color[j][2], color[j][3], color[j][4], color[j][5]), + F(" ] to Mix [ "), LIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]), F(" ]") + ); #endif } @@ -180,9 +174,9 @@ class Mixer { static float prev_z; // Update the current mix from the gradient for a given Z - static void update_gradient_for_z(const_float_t z); + static void update_gradient_for_z(const float z); static void update_gradient_for_planner_z(); - static void gradient_control(const_float_t z) { + static void gradient_control(const float z) { if (gradient.enabled) { if (z >= gradient.end_z) T(gradient.end_vtool); @@ -197,11 +191,10 @@ class Mixer { MIXER_STEPPER_LOOP(i) mix[i] = (mixer_perc_t)CEIL(100.0f * gradient.color[i] / ctot); #ifdef MIXER_NORMALIZER_DEBUG - SERIAL_ECHOPGM("Gradient [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, gradient.color[0], gradient.color[1], gradient.color[2], gradient.color[3], gradient.color[4], gradient.color[5]); - SERIAL_ECHOPGM(" ] to Mix [ "); - SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]); - SERIAL_ECHOLNPGM(" ]"); + SERIAL_ECHOLN( + F("Gradient [ "), LIST_N(MIXING_STEPPERS, gradient.color[0], gradient.color[1], gradient.color[2], gradient.color[3], gradient.color[4], gradient.color[5]), + F(" ] to Mix [ "), LIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]), F(" ]") + ); #endif } @@ -234,13 +227,7 @@ class Mixer { for (;;) { if (--runner < 0) runner = MIXING_STEPPERS - 1; accu[runner] += s_color[runner]; - if ( - #ifdef MIXER_ACCU_SIGNED - accu[runner] < 0 - #else - accu[runner] & COLOR_A_MASK - #endif - ) { + if (TERN(MIXER_ACCU_SIGNED, accu[runner] < 0, accu[runner] & COLOR_A_MASK)) { accu[runner] &= COLOR_MASK; return runner; } diff --git a/Marlin/src/feature/mmu/mmu.cpp b/Marlin/src/feature/mmu/mmu.cpp index 58c49ed224..b1e66cc425 100644 --- a/Marlin/src/feature/mmu/mmu.cpp +++ b/Marlin/src/feature/mmu/mmu.cpp @@ -24,7 +24,6 @@ #if HAS_PRUSA_MMU1 -#include "../../MarlinCore.h" #include "../../module/planner.h" #include "../../module/stepper.h" diff --git a/Marlin/src/feature/mmu/mmu2-serial-protocol.md b/Marlin/src/feature/mmu/mmu2-serial-protocol.md index 93135e406f..80480d15c7 100644 --- a/Marlin/src/feature/mmu/mmu2-serial-protocol.md +++ b/Marlin/src/feature/mmu/mmu2-serial-protocol.md @@ -1,5 +1,4 @@ -Startup sequence -================ +# Startup sequence When initialized, MMU sends @@ -8,9 +7,9 @@ When initialized, MMU sends We follow with - MMU <= 'S1\n' -- MMU => 'ok*Firmware version*\n' +- MMU => 'ok<_Firmware version_>\n' - MMU <= 'S2\n' -- MMU => 'ok*Build number*\n' +- MMU => 'ok<_Build number_>\n' #if (12V_mode) @@ -20,75 +19,60 @@ We follow with #endif - MMU <= 'P0\n' -- MMU => '*FINDA status*\n' +- MMU => '<_FINDA status_>\n' Now we are sure MMU is available and ready. If there was a timeout or other communication problem somewhere, printer will be killed. -- *Firmware version* is an integer value, but we don't care about it -- *Build number* is an integer value and has to be >=126, or =>132 if 12V mode is enabled -- *FINDA status* is 1 if the filament is loaded to the extruder, 0 otherwise +- <_Firmware version_> is an integer value, but we don't care about it. +- <_Build number_> is an integer value and has to be >=126, or =>132 if 12V mode is enabled. +- <_FINDA status_> is 1 if the filament is loaded to the extruder, 0 otherwise. +<_Build number_> is checked against the required value, if it does not match, printer is halted. -*Build number* is checked against the required value, if it does not match, printer is halted. +# Toolchange - - -Toolchange -========== - -- MMU <= 'T*Filament index*\n' +- MMU <= 'T<_Filament index_>\n' MMU sends - MMU => 'ok\n' -as soon as the filament is fed down to the extruder. We follow with +as soon as the filament is fed down to the extruder. We follow with: - MMU <= 'C0\n' -MMU will feed a few more millimeters of filament for the extruder gears to grab. +MMU will feed a few more millimeters of filament for the extruder gears to grab.\ When done, the MMU sends - MMU => 'ok\n' -We don't wait for a response here but immediately continue with the next G-code 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. - -FINDA status -============ +# FINDA status - MMU <= 'P0\n' -- MMU => '*FINDA status*\n' +- MMU => '<_FINDA status_>\n' -*FINDA status* is 1 if the is filament loaded to the extruder, 0 otherwise. This could be used as filament runout sensor if probed regularly. +_FINDA status_ is 1 if the is filament loaded to the extruder, 0 otherwise. This could be used as filament runout sensor if probed regularly. +# Load filament +- MMU <= 'L<_Filament index_>\n' -Load filament -============= - -- MMU <= 'L*Filament index*\n' - -MMU will feed filament down to the extruder, when done +MMU will feed filament down to the extruder, when done: - MMU => 'ok\n' - -Unload filament -============= +# Unload filament - MMU <= 'U0\n' -MMU will retract current filament from the extruder, when done +MMU will retract current filament from the extruder, when done: - MMU => 'ok\n' +# Eject filament - -Eject filament -============== - -- MMU <= 'E*Filament index*\n' +- MMU <= 'E<_Filament index_>\n' - MMU => 'ok\n' - diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index a4718b53d9..76e2b8505f 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -24,6 +24,10 @@ #if HAS_PRUSA_MMU2 +/** + * mmu2.cpp - Support for Průša MMU2 and MMU2S + */ + #include "mmu2.h" #include "../../lcd/menu/menu_mmu2.h" @@ -36,17 +40,16 @@ MMU2 mmu2; #include "../../module/temperature.h" #include "../../module/planner.h" #include "../../module/stepper.h" -#include "../../MarlinCore.h" #if ENABLED(HOST_PROMPT_SUPPORT) - #include "../../feature/host_actions.h" + #include "../host_actions.h" #endif #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" #endif -#define DEBUG_OUT ENABLED(MMU2_DEBUG) +#define DEBUG_OUT ENABLED(MMU_DEBUG) #include "../../core/debug_out.h" #define MMU_TODELAY 100 @@ -54,9 +57,10 @@ MMU2 mmu2; #define MMU_CMD_TIMEOUT 45000UL // 45s timeout for mmu commands (except P0) #define MMU_P0_TIMEOUT 3000UL // Timeout for P0 command: 3seconds -#define MMU2_COMMAND(S) tx_str(F(S "\n")) +#define MMU2_SEND(S) tx_str(F(S "\n")) +#define MMU2_RECV(S) rx_str(F(S "\n")) -#if ENABLED(MMU_EXTRUDER_SENSOR) +#if ENABLED(MMU2_EXTRUDER_SENSOR) uint8_t mmu_idl_sens = 0; static bool mmu_loading_flag = false; #endif @@ -75,7 +79,7 @@ MMU2 mmu2; #define MMU2_NO_TOOL 99 #define MMU_BAUD 115200 -bool MMU2::_enabled, MMU2::ready, MMU2::mmu_print_saved; +bool MMU2::_enabled, MMU2::ready; #if HAS_PRUSA_MMU2S bool MMU2::mmu2s_triggered; #endif @@ -83,7 +87,6 @@ uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder; int8_t MMU2::state = 0; volatile int8_t MMU2::finda = 1; volatile bool MMU2::finda_runout_valid; -int16_t MMU2::version = -1, MMU2::buildnr = -1; millis_t MMU2::prev_request, MMU2::prev_P0_request; char MMU2::rx_buffer[MMU_RX_SIZE], MMU2::tx_buffer[MMU_TX_SIZE]; @@ -92,14 +95,11 @@ struct E_Step { feedRate_t feedRate; //!< feed rate in mm/s }; -static constexpr E_Step - ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE } - , load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE } - #if HAS_PRUSA_MMU2S - , can_load_sequence[] PROGMEM = { MMU2_CAN_LOAD_SEQUENCE } - , can_load_increment_sequence[] PROGMEM = { MMU2_CAN_LOAD_INCREMENT_SEQUENCE } - #endif -; +inline void unscaled_mmu2_e_move(const float dist, const feedRate_t fr_mm_s, const bool sync=true) { + current_position.e += dist / planner.e_factor[active_extruder]; + line_to_current_position(fr_mm_s); + if (sync) planner.synchronize(); +} MMU2::MMU2() { rx_buffer[0] = '\0'; @@ -109,12 +109,12 @@ void MMU2::init() { set_runout_valid(false); - #if PIN_EXISTS(MMU2_RST) - WRITE(MMU2_RST_PIN, HIGH); - SET_OUTPUT(MMU2_RST_PIN); + #if PIN_EXISTS(MMU_RST) + WRITE(MMU_RST_PIN, HIGH); + SET_OUTPUT(MMU_RST_PIN); #endif - MMU2_SERIAL.begin(MMU_BAUD); + MMU_SERIAL.begin(MMU_BAUD); extruder = MMU2_NO_TOOL; safe_delay(10); @@ -126,21 +126,21 @@ void MMU2::init() { void MMU2::reset() { DEBUG_ECHOLNPGM("MMU <= reset"); - #if PIN_EXISTS(MMU2_RST) - WRITE(MMU2_RST_PIN, LOW); + #if PIN_EXISTS(MMU_RST) + WRITE(MMU_RST_PIN, LOW); safe_delay(20); - WRITE(MMU2_RST_PIN, HIGH); + WRITE(MMU_RST_PIN, HIGH); #else - MMU2_COMMAND("X0"); // Send soft reset + MMU2_SEND("X0"); // Send soft reset #endif } -uint8_t MMU2::get_current_tool() { - return extruder == MMU2_NO_TOOL ? -1 : extruder; -} +int8_t MMU2::get_current_tool() { return extruder == MMU2_NO_TOOL ? -1 : extruder; } -#if EITHER(HAS_PRUSA_MMU2S, MMU_EXTRUDER_SENSOR) +#if ANY(HAS_PRUSA_MMU2S, MMU2_EXTRUDER_SENSOR) #define FILAMENT_PRESENT() (READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE) +#else + #define FILAMENT_PRESENT() true #endif void mmu2_attn_buzz(const bool two=false) { @@ -148,6 +148,7 @@ void mmu2_attn_buzz(const bool two=false) { if (two) { BUZZ(10, 0); BUZZ(200, 404); } } +// Avoiding sscanf significantly reduces build size void MMU2::mmu_loop() { switch (state) { @@ -157,14 +158,12 @@ void MMU2::mmu_loop() { case -1: if (rx_start()) { prev_P0_request = millis(); // Initialize finda sensor timeout - DEBUG_ECHOLNPGM("MMU => 'start'"); DEBUG_ECHOLNPGM("MMU <= 'S1'"); - - MMU2_COMMAND("S1"); // Read Version + MMU2_SEND("S1"); // Read Version state = -2; } - else if (millis() > 30000) { // 30sec after reset disable MMU + else if (ELAPSED(millis(), prev_request, 30000)) { // 30sec after reset disable MMU SERIAL_ECHOLNPGM("MMU not responding - DISABLED"); state = 0; } @@ -172,55 +171,48 @@ void MMU2::mmu_loop() { case -2: if (rx_ok()) { - sscanf(rx_buffer, "%huok\n", &version); - + const uint16_t version = uint16_t(strtoul(rx_buffer, nullptr, 10)); DEBUG_ECHOLNPGM("MMU => ", version, "\nMMU <= 'S2'"); - - MMU2_COMMAND("S2"); // Read Build Number + MMU2_SEND("S2"); // Read Build Number state = -3; } break; case -3: if (rx_ok()) { - sscanf(rx_buffer, "%huok\n", &buildnr); - + const uint16_t buildnr = uint16_t(strtoul(rx_buffer, nullptr, 10)); DEBUG_ECHOLNPGM("MMU => ", buildnr); - check_version(); + check_version(buildnr); #if ENABLED(MMU2_MODE_12V) DEBUG_ECHOLNPGM("MMU <= 'M1'"); - - MMU2_COMMAND("M1"); // Stealth Mode + MMU2_SEND("M1"); // Stealth Mode state = -5; - #else DEBUG_ECHOLNPGM("MMU <= 'P0'"); - - MMU2_COMMAND("P0"); // Read FINDA + MMU2_SEND("P0"); // Read FINDA state = -4; #endif } break; #if ENABLED(MMU2_MODE_12V) - case -5: - // response to M1 - if (rx_ok()) { - DEBUG_ECHOLNPGM("MMU => ok"); - - DEBUG_ECHOLNPGM("MMU <= 'P0'"); - - MMU2_COMMAND("P0"); // Read FINDA - state = -4; - } - break; + case -5: + // response to M1 + if (rx_ok()) { + DEBUG_ECHOLNPGM("MMU => ok"); + DEBUG_ECHOLNPGM("MMU <= 'P0'"); + MMU2_SEND("P0"); // Read FINDA + state = -4; + } + break; #endif case -4: if (rx_ok()) { - sscanf(rx_buffer, "%hhuok\n", &finda); + const uint8_t findex = uint8_t(rx_buffer[0] - '0'); + if (findex <= 1) finda = findex; DEBUG_ECHOLNPGM("MMU => ", finda, "\nMMU - ENABLED"); @@ -237,7 +229,7 @@ void MMU2::mmu_loop() { const int filament = cmd - MMU_CMD_T0; DEBUG_ECHOLNPGM("MMU <= T", filament); tx_printf(F("T%d\n"), filament); - TERN_(MMU_EXTRUDER_SENSOR, mmu_idl_sens = 1); // enable idler sensor, if any + TERN_(MMU2_EXTRUDER_SENSOR, mmu_idl_sens = 1); // enable idler sensor, if any state = 3; // wait for response } else if (WITHIN(cmd, MMU_CMD_L0, MMU_CMD_L0 + EXTRUDERS - 1)) { @@ -250,14 +242,13 @@ void MMU2::mmu_loop() { else if (cmd == MMU_CMD_C0) { // continue loading DEBUG_ECHOLNPGM("MMU <= 'C0'"); - MMU2_COMMAND("C0"); + MMU2_SEND("C0"); state = 3; // wait for response } else if (cmd == MMU_CMD_U0) { // unload current DEBUG_ECHOLNPGM("MMU <= 'U0'"); - - MMU2_COMMAND("U0"); + MMU2_SEND("U0"); state = 3; // wait for response } else if (WITHIN(cmd, MMU_CMD_E0, MMU_CMD_E0 + EXTRUDERS - 1)) { @@ -270,7 +261,7 @@ void MMU2::mmu_loop() { else if (cmd == MMU_CMD_R0) { // recover after eject DEBUG_ECHOLNPGM("MMU <= 'R0'"); - MMU2_COMMAND("R0"); + MMU2_SEND("R0"); state = 3; // wait for response } else if (WITHIN(cmd, MMU_CMD_F0, MMU_CMD_F0 + EXTRUDERS - 1)) { @@ -284,8 +275,8 @@ void MMU2::mmu_loop() { last_cmd = cmd; cmd = MMU_CMD_NONE; } - else if (ELAPSED(millis(), prev_P0_request + 300)) { - MMU2_COMMAND("P0"); // Read FINDA + else if (ELAPSED(millis(), prev_P0_request, 300)) { + MMU2_SEND("P0"); // Read FINDA state = 2; // wait for response } @@ -294,27 +285,28 @@ void MMU2::mmu_loop() { case 2: // response to command P0 if (rx_ok()) { - sscanf(rx_buffer, "%hhuok\n", &finda); + const uint8_t findex = uint8_t(rx_buffer[0] - '0'); + if (findex <= 1) finda = findex; // This is super annoying. Only activate if necessary - // if (finda_runout_valid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6); + //if (finda_runout_valid) DEBUG_ECHOLNPGM("MMU <= 'P0'\nMMU => ", p_float_t(finda, 6)); if (!finda && finda_runout_valid) filament_runout(); if (cmd == MMU_CMD_NONE) ready = true; state = 1; } - else if (ELAPSED(millis(), prev_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s) + else if (ELAPSED(millis(), prev_request, MMU_P0_TIMEOUT)) // Resend request after timeout (3s) state = 1; TERN_(HAS_PRUSA_MMU2S, check_filament()); break; case 3: // response to mmu commands - #if ENABLED(MMU_EXTRUDER_SENSOR) + #if ENABLED(MMU2_EXTRUDER_SENSOR) if (mmu_idl_sens) { if (FILAMENT_PRESENT() && mmu_loading_flag) { DEBUG_ECHOLNPGM("MMU <= 'A'"); - MMU2_COMMAND("A"); // send 'abort' request + MMU2_SEND("A"); // send 'abort' request mmu_idl_sens = 0; DEBUG_ECHOLNPGM("MMU IDLER_SENSOR = 0 - ABORT"); } @@ -327,9 +319,9 @@ void MMU2::mmu_loop() { const bool keep_trying = !mmu2s_triggered && last_cmd == MMU_CMD_C0; if (keep_trying) { // MMU ok received but filament sensor not triggered, retrying... - DEBUG_ECHOLNPGM("MMU => 'ok' (filament not present in gears)"); + DEBUG_ECHOLNPGM("MMU => 'ok' (no filament in gears)"); DEBUG_ECHOLNPGM("MMU <= 'C0' (keep trying)"); - MMU2_COMMAND("C0"); + MMU2_SEND("C0"); } #else constexpr bool keep_trying = false; @@ -342,7 +334,7 @@ void MMU2::mmu_loop() { last_cmd = MMU_CMD_NONE; } } - else if (ELAPSED(millis(), prev_request + MMU_CMD_TIMEOUT)) { + else if (ELAPSED(millis(), prev_request, MMU_CMD_TIMEOUT)) { // resend request after timeout if (last_cmd) { DEBUG_ECHOLNPGM("MMU retry"); @@ -361,7 +353,7 @@ void MMU2::mmu_loop() { */ bool MMU2::rx_start() { // check for start message - return rx_str(F("start\n")); + return MMU2_RECV("start"); } /** @@ -372,8 +364,8 @@ bool MMU2::rx_str(FSTR_P fstr) { uint8_t i = strlen(rx_buffer); - while (MMU2_SERIAL.available()) { - rx_buffer[i++] = MMU2_SERIAL.read(); + while (MMU_SERIAL.available()) { + rx_buffer[i++] = MMU_SERIAL.read(); if (i == sizeof(rx_buffer) - 1) { DEBUG_ECHOLNPGM("rx buffer overrun"); @@ -404,7 +396,7 @@ bool MMU2::rx_str(FSTR_P fstr) { void MMU2::tx_str(FSTR_P fstr) { clear_rx_buffer(); PGM_P pstr = FTOP(fstr); - while (const char c = pgm_read_byte(pstr)) { MMU2_SERIAL.write(c); pstr++; } + while (const char c = pgm_read_byte(pstr)) { MMU_SERIAL.write(c); pstr++; } prev_request = millis(); } @@ -414,7 +406,7 @@ void MMU2::tx_str(FSTR_P fstr) { void MMU2::tx_printf(FSTR_P format, int argument = -1) { clear_rx_buffer(); const uint8_t len = sprintf_P(tx_buffer, FTOP(format), argument); - LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); + for (uint8_t i = 0; i < len; ++i) MMU_SERIAL.write(tx_buffer[i]); prev_request = millis(); } @@ -424,7 +416,7 @@ void MMU2::tx_printf(FSTR_P format, int argument = -1) { void MMU2::tx_printf(FSTR_P format, int argument1, int argument2) { clear_rx_buffer(); const uint8_t len = sprintf_P(tx_buffer, FTOP(format), argument1, argument2); - LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); + for (uint8_t i = 0; i < len; ++i) MMU_SERIAL.write(tx_buffer[i]); prev_request = millis(); } @@ -432,7 +424,7 @@ void MMU2::tx_printf(FSTR_P format, int argument1, int argument2) { * Empty the rx buffer */ void MMU2::clear_rx_buffer() { - while (MMU2_SERIAL.available()) MMU2_SERIAL.read(); + while (MMU_SERIAL.available()) MMU_SERIAL.read(); rx_buffer[0] = '\0'; } @@ -440,7 +432,7 @@ void MMU2::clear_rx_buffer() { * Check if we received 'ok' from MMU */ bool MMU2::rx_ok() { - if (rx_str(F("ok\n"))) { + if (MMU2_RECV("ok")) { prev_P0_request = millis(); return true; } @@ -450,10 +442,10 @@ bool MMU2::rx_ok() { /** * Check if MMU has compatible firmware */ -void MMU2::check_version() { +void MMU2::check_version(const uint16_t buildnr) { if (buildnr < MMU_REQUIRED_FW_BUILDNR) { SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required."); - kill(GET_TEXT_F(MSG_KILL_MMU2_FIRMWARE)); + marlin.kill(GET_TEXT_F(MSG_KILL_MMU2_FIRMWARE)); } } @@ -466,12 +458,19 @@ static void mmu2_not_responding() { BUZZ(100, 659); } +inline void beep_bad_cmd() { BUZZ(400, 40); } + #if HAS_PRUSA_MMU2S + /** + * Load filament until the sensor at the gears is triggered + * and give up after a number of attempts set with MMU2_C0_RETRY. + * Each try has a timeout before returning a fail state. + */ bool MMU2::load_to_gears() { command(MMU_CMD_C0); manage_response(true, true); - LOOP_L_N(i, MMU2_C0_RETRY) { // Keep loading until filament reaches gears + for (uint8_t i = 0; i < MMU2_C0_RETRY; ++i) { // Keep loading until filament reaches gears if (mmu2s_triggered) break; command(MMU_CMD_C0); manage_response(true, true); @@ -492,6 +491,11 @@ static void mmu2_not_responding() { set_runout_valid(false); if (index != extruder) { + if (ENABLED(MMU_IR_UNLOAD_MOVE) && FILAMENT_PRESENT()) { + DEBUG_ECHOLNPGM("Unloading\n"); + while (FILAMENT_PRESENT()) // Filament present? Keep unloading. + unscaled_mmu2_e_move(-0.25, MMM_TO_MMS(120)); // 0.25mm is a guessed value. Adjust to preference. + } stepper.disable_extruder(); ui.status_printf(0, GET_TEXT_F(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); @@ -525,17 +529,17 @@ static void mmu2_not_responding() { switch (*special) { case '?': { - #if ENABLED(MMU2_MENUS) + #if ENABLED(MMU_MENUS) const uint8_t index = mmu2_choose_filament(); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - load_filament_to_nozzle(index); + load_to_nozzle(index); #else - ERR_BUZZ(); + beep_bad_cmd(); #endif } break; case 'x': { - #if ENABLED(MMU2_MENUS) + #if ENABLED(MMU_MENUS) planner.synchronize(); const uint8_t index = mmu2_choose_filament(); stepper.disable_extruder(); @@ -549,20 +553,20 @@ static void mmu2_not_responding() { active_extruder = 0; } #else - ERR_BUZZ(); + beep_bad_cmd(); #endif } break; case 'c': { while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - load_to_nozzle(); + load_to_nozzle_sequence(); } break; } set_runout_valid(true); } -#elif ENABLED(MMU_EXTRUDER_SENSOR) +#elif ENABLED(MMU2_EXTRUDER_SENSOR) /** * Handle tool change @@ -585,7 +589,7 @@ static void mmu2_not_responding() { command(MMU_CMD_T0 + index); manage_response(true, true); mmu_continue_loading(); - command(MMU_CMD_C0); + //command(MMU_CMD_C0); extruder = index; active_extruder = 0; @@ -613,18 +617,18 @@ static void mmu2_not_responding() { switch (*special) { case '?': { DEBUG_ECHOLNPGM("case ?\n"); - #if ENABLED(MMU2_MENUS) + #if ENABLED(MMU_MENUS) uint8_t index = mmu2_choose_filament(); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - load_filament_to_nozzle(index); + load_to_nozzle(index); #else - ERR_BUZZ(); + beep_bad_cmd(); #endif } break; case 'x': { DEBUG_ECHOLNPGM("case x\n"); - #if ENABLED(MMU2_MENUS) + #if ENABLED(MMU_MENUS) planner.synchronize(); uint8_t index = mmu2_choose_filament(); stepper.disable_extruder(); @@ -638,14 +642,14 @@ static void mmu2_not_responding() { extruder = index; active_extruder = 0; #else - ERR_BUZZ(); + beep_bad_cmd(); #endif } break; case 'c': { DEBUG_ECHOLNPGM("case c\n"); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); + load_to_nozzle_sequence(); } break; } @@ -653,20 +657,41 @@ static void mmu2_not_responding() { } void MMU2::mmu_continue_loading() { - for (uint8_t i = 0; i < MMU_LOADING_ATTEMPTS_NR; i++) { - DEBUG_ECHOLNPGM("Additional load attempt #", i); - if (FILAMENT_PRESENT()) break; + // Try to load the filament a limited number of times + bool fil_present = 0; + for (uint8_t i = 0; i < MMU2_LOADING_ATTEMPTS_NR; i++) { + DEBUG_ECHOLNPGM("Load attempt #", i + 1); + + // Done as soon as filament is present + fil_present = FILAMENT_PRESENT(); + if (fil_present) break; + + // Attempt to load the filament, 1mm at a time, for 3s command(MMU_CMD_C0); + stepper.enable_extruder(); + const millis_t expire_ms = millis() + 3000; + do { + current_position.e += 1; + line_to_current_position(MMU_LOAD_FEEDRATE); + planner.synchronize(); + // When (T0 rx->ok) load is ready, but in fact it did not load + // successfully or an overload created pressure in the extruder. + // Send (C0) to load more and move E_AXIS a little to release pressure. + if ((fil_present = FILAMENT_PRESENT())) MMU2_SEND("A"); + } while (!fil_present && PENDING(millis(), expire_ms)); + stepper.disable_extruder(); manage_response(true, true); } - if (!FILAMENT_PRESENT()) { + + // Was the filament still missing in the last check? + if (!fil_present) { DEBUG_ECHOLNPGM("Filament never reached sensor, runout"); filament_runout(); } mmu_idl_sens = 0; } -#else // !HAS_PRUSA_MMU2S && !MMU_EXTRUDER_SENSOR +#else // !HAS_PRUSA_MMU2S && !MMU2_EXTRUDER_SENSOR /** * Handle tool change @@ -682,7 +707,7 @@ static void mmu2_not_responding() { command(MMU_CMD_T0 + index); manage_response(true, true); command(MMU_CMD_C0); - extruder = index; //filament change is finished + extruder = index; // Filament change is finished active_extruder = 0; stepper.enable_extruder(); SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder); @@ -707,18 +732,18 @@ static void mmu2_not_responding() { switch (*special) { case '?': { DEBUG_ECHOLNPGM("case ?\n"); - #if ENABLED(MMU2_MENUS) + #if ENABLED(MMU_MENUS) uint8_t index = mmu2_choose_filament(); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - load_filament_to_nozzle(index); + load_to_nozzle(index); #else - ERR_BUZZ(); + beep_bad_cmd(); #endif } break; case 'x': { DEBUG_ECHOLNPGM("case x\n"); - #if ENABLED(MMU2_MENUS) + #if ENABLED(MMU_MENUS) planner.synchronize(); uint8_t index = mmu2_choose_filament(); stepper.disable_extruder(); @@ -731,14 +756,14 @@ static void mmu2_not_responding() { extruder = index; active_extruder = 0; #else - ERR_BUZZ(); + beep_bad_cmd(); #endif } break; case 'c': { DEBUG_ECHOLNPGM("case c\n"); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); - execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); + load_to_nozzle_sequence(); } break; } @@ -760,10 +785,10 @@ void MMU2::command(const uint8_t mmu_cmd) { * Wait for response from MMU */ bool MMU2::get_response() { - while (cmd != MMU_CMD_NONE) idle(); + while (cmd != MMU_CMD_NONE) marlin.idle(); while (!ready) { - idle(); + marlin.idle(); if (state != 3) break; } @@ -779,8 +804,7 @@ bool MMU2::get_response() { void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { constexpr xyz_pos_t park_point = NOZZLE_PARK_POINT; - bool response = false; - mmu_print_saved = false; + bool response = false, mmu_print_saved = false; xyz_pos_t resume_position; celsius_t resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); @@ -802,8 +826,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); resume_position = current_position; - if (move_axes && all_axes_homed()) - nozzle.park(0, park_point /*= NOZZLE_PARK_POINT*/); + if (move_axes && all_axes_homed()) nozzle.park(0, park_point); if (turn_off_nozzle) thermalManager.setTargetHotend(0, active_extruder); @@ -811,13 +834,12 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { } } else if (mmu_print_saved) { - SERIAL_ECHOLNPGM("MMU starts responding\n"); + SERIAL_ECHOLNPGM("\nMMU starts responding"); if (turn_off_nozzle && resume_hotend_temp) { thermalManager.setTargetHotend(resume_hotend_temp, active_extruder); LCD_MESSAGE(MSG_HEATING); ERR_BUZZ(); - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(1000); } @@ -830,7 +852,6 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { if (move_axes && all_axes_homed()) { // Move XY to starting position, then Z do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); - // Move Z_AXIS to saved position do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); } @@ -861,27 +882,28 @@ void MMU2::filament_runout() { if (cmd == MMU_CMD_NONE && last_cmd == MMU_CMD_C0) { if (present && !mmu2s_triggered) { DEBUG_ECHOLNPGM("MMU <= 'A'"); - tx_str(F("A\n")); + MMU2_SEND("A"); } // Slowly spin the extruder during C0 else { - while (planner.movesplanned() < 3) { - current_position.e += 0.25; - line_to_current_position(MMM_TO_MMS(120)); - } + while (planner.movesplanned() < 3) + unscaled_mmu2_e_move(0.25, MMM_TO_MMS(120), false); } } mmu2s_triggered = present; } bool MMU2::can_load() { - execute_extruder_sequence((const E_Step *)can_load_sequence, COUNT(can_load_sequence)); + static constexpr E_Step can_load_sequence[] PROGMEM = { MMU2_CAN_LOAD_SEQUENCE }, + can_load_increment_sequence[] PROGMEM = { MMU2_CAN_LOAD_INCREMENT_SEQUENCE }; + + execute_extruder_sequence(can_load_sequence, COUNT(can_load_sequence)); int filament_detected_count = 0; const int steps = (MMU2_CAN_LOAD_RETRACT) / (MMU2_CAN_LOAD_INCREMENT); DEBUG_ECHOLNPGM("MMU can_load:"); - LOOP_L_N(i, steps) { - execute_extruder_sequence((const E_Step *)can_load_increment_sequence, COUNT(can_load_increment_sequence)); + for (uint8_t i = 0; i < steps; ++i) { + execute_extruder_sequence(can_load_increment_sequence, COUNT(can_load_increment_sequence)); check_filament(); // Don't trust the idle function DEBUG_CHAR(mmu2s_triggered ? 'O' : 'o'); if (mmu2s_triggered) ++filament_detected_count; @@ -899,7 +921,7 @@ void MMU2::filament_runout() { #endif // Load filament into MMU2 -void MMU2::load_filament(const uint8_t index) { +void MMU2::load_to_feeder(const uint8_t index) { if (!_enabled) return; command(MMU_CMD_L0 + index); @@ -910,8 +932,7 @@ void MMU2::load_filament(const uint8_t index) { /** * Switch material and load to nozzle */ -bool MMU2::load_filament_to_nozzle(const uint8_t index) { - +bool MMU2::load_to_nozzle(const uint8_t index) { if (!_enabled) return false; if (thermalManager.tooColdToExtrude(active_extruder)) { @@ -920,6 +941,13 @@ bool MMU2::load_filament_to_nozzle(const uint8_t index) { return false; } + if (TERN0(MMU_IR_UNLOAD_MOVE, index != extruder) && FILAMENT_PRESENT()) { + DEBUG_ECHOLNPGM("Unloading\n"); + ramming_sequence(); // Unloading instructions from printer side when operating LCD + while (FILAMENT_PRESENT()) // Filament present? Keep unloading. + unscaled_mmu2_e_move(-0.25, MMM_TO_MMS(120)); // 0.25mm is a guessed value. Adjust to preference. + } + stepper.disable_extruder(); command(MMU_CMD_T0 + index); manage_response(true, true); @@ -929,23 +957,12 @@ bool MMU2::load_filament_to_nozzle(const uint8_t index) { mmu_loop(); extruder = index; active_extruder = 0; - load_to_nozzle(); + load_to_nozzle_sequence(); mmu2_attn_buzz(); } return success; } -/** - * Load filament to nozzle of multimaterial printer - * - * This function is used only after T? (user select filament) and M600 (change filament). - * It is not used after T0 .. T4 command (select filament), in such case, G-code is responsible for loading - * filament to nozzle. - */ -void MMU2::load_to_nozzle() { - execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence)); -} - bool MMU2::eject_filament(const uint8_t index, const bool recover) { if (!_enabled) return false; @@ -958,20 +975,17 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { LCD_MESSAGE(MSG_MMU2_EJECTING_FILAMENT); - stepper.enable_extruder(); - current_position.e -= MMU2_FILAMENTCHANGE_EJECT_FEED; - line_to_current_position(MMM_TO_MMS(2500)); - planner.synchronize(); + unscaled_mmu2_e_move(-(MMU2_FILAMENTCHANGE_EJECT_FEED), MMM_TO_MMS(2500)); command(MMU_CMD_E0 + index); manage_response(false, false); if (recover) { - LCD_MESSAGE(MSG_MMU2_EJECT_RECOVER); + LCD_MESSAGE(MSG_MMU2_REMOVE_AND_CLICK); + mmu2_attn_buzz(); + TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_MMU2_EJECT_RECOVER))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_MMU2_EJECT_RECOVER))); + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response()); mmu2_attn_buzz(); - TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, F("MMU2 Eject Recover"), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("MMU2 Eject Recover"))); - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); - mmu2_attn_buzz(true); command(MMU_CMD_R0); manage_response(false, false); @@ -1005,7 +1019,7 @@ bool MMU2::unload() { } // Unload sequence to optimize shape of the tip of the unloaded filament - execute_extruder_sequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step)); + ramming_sequence(); command(MMU_CMD_U0); manage_response(false, true); @@ -1020,23 +1034,27 @@ bool MMU2::unload() { return true; } -void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { +void MMU2::ramming_sequence() { + static const E_Step sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE }; + execute_extruder_sequence(sequence, COUNT(sequence)); +} + +void MMU2::load_to_nozzle_sequence() { + static const E_Step sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE }; + execute_extruder_sequence(sequence, COUNT(sequence)); +} + +void MMU2::execute_extruder_sequence(const E_Step * const sequence, const uint8_t steps) { planner.synchronize(); - stepper.enable_extruder(); - const E_Step* step = sequence; + const E_Step *step = sequence; - LOOP_L_N(i, steps) { + for (uint8_t i = 0; i < steps; ++i) { const float es = pgm_read_float(&(step->extrude)); const feedRate_t fr_mm_m = pgm_read_float(&(step->feedRate)); - DEBUG_ECHO_MSG("E step ", es, "/", fr_mm_m); - - current_position.e += es; - line_to_current_position(MMM_TO_MMS(fr_mm_m)); - planner.synchronize(); - + unscaled_mmu2_e_move(es, MMM_TO_MMS(fr_mm_m)); step++; } diff --git a/Marlin/src/feature/mmu/mmu2.h b/Marlin/src/feature/mmu/mmu2.h index 7d3d9ec4df..117b3a6046 100644 --- a/Marlin/src/feature/mmu/mmu2.h +++ b/Marlin/src/feature/mmu/mmu2.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * mmu2.h - Support for Průša MMU2 and MMU2S + */ + #include "../../inc/MarlinConfig.h" #if HAS_FILAMENT_SENSOR @@ -47,13 +51,12 @@ public: static void mmu_loop(); static void tool_change(const uint8_t index); static void tool_change(const char *special); - static uint8_t get_current_tool(); + static int8_t get_current_tool(); static void set_filament_type(const uint8_t index, const uint8_t type); static bool unload(); - static void load_filament(uint8_t); - static void load_all(); - static bool load_filament_to_nozzle(const uint8_t index); + static void load_to_feeder(const uint8_t index); + static bool load_to_nozzle(const uint8_t index); static bool eject_filament(const uint8_t index, const bool recover); private: @@ -65,14 +68,15 @@ private: static bool rx_ok(); static bool rx_start(); - static void check_version(); + static void check_version(const uint16_t buildnr); static void command(const uint8_t cmd); static bool get_response(); static void manage_response(const bool move_axes, const bool turn_off_nozzle); - static void load_to_nozzle(); - static void execute_extruder_sequence(const E_Step * sequence, int steps); + static void execute_extruder_sequence(const E_Step * const sequence, const uint8_t steps); + static void ramming_sequence(); + static void load_to_nozzle_sequence(); static void filament_runout(); @@ -85,17 +89,17 @@ private: FORCE_INLINE static bool load_to_gears() { return true; } #endif - #if ENABLED(MMU_EXTRUDER_SENSOR) + #if ENABLED(MMU2_EXTRUDER_SENSOR) + #define MMU_LOAD_FEEDRATE 19.02f // (mm/s) static void mmu_continue_loading(); #endif - static bool _enabled, ready, mmu_print_saved; + static bool _enabled, ready; static uint8_t cmd, cmd_arg, last_cmd, extruder; static int8_t state; static volatile int8_t finda; static volatile bool finda_runout_valid; - static int16_t version, buildnr; static millis_t prev_request, prev_P0_request; static char rx_buffer[MMU_RX_SIZE], tx_buffer[MMU_TX_SIZE]; diff --git a/Marlin/src/feature/mmu3/SpoolJoin.cpp b/Marlin/src/feature/mmu3/SpoolJoin.cpp new file mode 100644 index 0000000000..f27d2bc7e9 --- /dev/null +++ b/Marlin/src/feature/mmu3/SpoolJoin.cpp @@ -0,0 +1,73 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * SpoolJoin.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "SpoolJoin.h" +#include "../../module/settings.h" +#include "../../core/language.h" + +SpoolJoin spooljoin; + +bool SpoolJoin::enabled; // Initialized by settings.load +int SpoolJoin::epprom_addr; // Initialized by settings.load +uint8_t SpoolJoin::currentMMUSlot; + +SpoolJoin::SpoolJoin() { setSlot(0); } + +void SpoolJoin::initStatus() { + // Useful information to see during bootup + SERIAL_ECHOLN(F("SpoolJoin is "), enabled ? F("On") : F("Off")); +} + +void SpoolJoin::toggle() { + // Toggle enabled value. + FLIP(enabled); + + // Following Prusa's implementation let's save the value to the EEPROM + // TODO: Move to settings.cpp + #if ENABLED(EEPROM_SETTINGS) + persistentStore.access_start(); + persistentStore.write_data(epprom_addr, enabled); + persistentStore.access_finish(); + settings.save(); + #endif +} + +bool SpoolJoin::isEnabled() { return enabled; } + +void SpoolJoin::setSlot(const uint8_t slot) { currentMMUSlot = slot; } + +uint8_t SpoolJoin::nextSlot() { + SERIAL_ECHOPGM("SpoolJoin: ", currentMMUSlot); + if (++currentMMUSlot >= 4) currentMMUSlot = 0; + SERIAL_ECHOLNPGM(" -> ", currentMMUSlot); + return currentMMUSlot; +} + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/SpoolJoin.h b/Marlin/src/feature/mmu3/SpoolJoin.h new file mode 100644 index 0000000000..b205d26ef5 --- /dev/null +++ b/Marlin/src/feature/mmu3/SpoolJoin.h @@ -0,0 +1,72 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * SpoolJoin.h + */ + +#include "../../MarlinCore.h" + +#include + +// See documentation here: https://help.prusa3d.com/article/spooljoin-mmu2s_134252 + +class SpoolJoin { +public: + SpoolJoin(); + + enum class EEPROM : uint8_t { + Unknown, //!< SpoolJoin is unknown while printer is booting up + Enabled, //!< SpoolJoin is enabled in EEPROM + Disabled, //!< SpoolJoin is disabled in EEPROM + Empty = 0xFF //!< EEPROM has not been set before and all bits are 1 (0xFF) - either a new printer or user erased the memory + }; + + // @brief Contrary to Prusa's implementation we store the enabled status in a variable + static int epprom_addr; + static bool enabled; + + // @brief Called when EEPROM is ready to be read + static void initStatus(); + + // @brief Toggle SpoolJoin + static void toggle(); + + // @brief Check if SpoolJoin is enabled + // @return true if enabled, false if disabled + static bool isEnabled(); + + // @brief Update the saved MMU slot number so SpoolJoin can determine the next slot to use + // @param slot number of the slot to set + static void setSlot(const uint8_t slot); + + // @brief Fetch the next slot number (0 to 4). + // When filament slot 4 is depleted, the next slot should be 0. + // @return the next slot (0 to 4) + static uint8_t nextSlot(); + +private: + static uint8_t currentMMUSlot; //!< Currently used slot (0 to 4) +}; + +extern SpoolJoin spooljoin; diff --git a/Marlin/src/feature/mmu3/mmu3-serial-protocol.md b/Marlin/src/feature/mmu3/mmu3-serial-protocol.md new file mode 100644 index 0000000000..0d0f7ac6e0 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3-serial-protocol.md @@ -0,0 +1,172 @@ +# MMU3 Messages + +Starting with the version 2.0.19 of the MMU firmware, requests and responses have a trailing section that contains the CRC8 of the original message. The general structure is as follows: + +``` +Requests (what Marlin requests): +MMU3:>{RequestMsgCode}{Value}*{CRC8}\n + +Responses (what MMU responds with): +MMU3:<{RequestMsgCode}{Value} {ResponseMsgParamCode}{paramValue}*{CRC8}\n +``` + +An example of that would be: + +``` +MMU3:>S0*c6\n +MMU3:S1*ad\n +MMU3:S2*10\n +MMU3:S0*c6\n +MMU3:>S0*c6\n +MMU3:>S0*c6\n +... +``` + +Once communication is established the MMU responds with: + +``` +MMU3:S1*ad\n +MMU3:S2*10\n +MMU3:M1*{CRC8}; +MMU3:<---nothing--- +``` + +``` +MMU3:>P0 +MMU3:T{Filament index}*{CRC8}\n +MMU3:T0*{CRC8}\n + +MMU3:>Q0*{CRC8}\n +MMU3: FeedingToFinda + +MMU3:>Q0*{CRC8}\n +MMU3: FeedingToNozzle +``` + +As soon as the filament is fed down to the extruder we follow with: + +``` +MMU3:>C0*{CRC8}\n +``` + +The MMU will feed a few more millimeters of filament for the extruder gears to grab. When done, the MMU sends: + +``` +MMU3:>Q0*{CRC8}\n +MMU3: FinishingMoves +``` + +After the `T0*P9` response we immediately continue with the next G-code which should be one or more extruder moves to feed the filament into the hotend. + +## FINDA status + +``` +MMU3:>P0*{CRC8}\n +``` + +If the filament is loaded to the extruder, FINDA status is 1 and the MMU responds with: + +``` +MMU3:L{Filament index}*{CRC8}\n +MMU3:Q0*{CRC8}\n +``` + +The MMU will respond with status messages: + +``` +MMU3:Q0*{CRC8}\n +MMU3: 'ok\n'` + +## Eject filament + +- `MMU <= 'E*Filament index*\n'` +- `MMU => 'ok\n'` diff --git a/Marlin/src/feature/mmu3/mmu3.cpp b/Marlin/src/feature/mmu3/mmu3.cpp new file mode 100644 index 0000000000..dd06126724 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3.cpp @@ -0,0 +1,1184 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "mmu3.h" +#include "mmu3_error_converter.h" +#include "mmu3_fsensor.h" +#include "mmu3_log.h" +#include "mmu3_marlin.h" +#include "mmu3_marlin_macros.h" +#include "mmu3_power.h" +#include "mmu3_progress_converter.h" +#include "mmu3_reporting.h" + +#include "SpoolJoin.h" + +#include "../../inc/MarlinConfig.h" + +#include "../../lcd/marlinui.h" +#include "../../module/planner.h" +#include "../../module/motion.h" +#include "../../gcode/parser.h" +#include "../../gcode/queue.h" +#include "../runout.h" +#if HAS_LEVELING + #include "../bedlevel/bedlevel.h" +#endif +#include "../pause.h" +#include "../../libs/stopwatch.h" + +// As of FW 3.12 we only support building the FW with only one extruder, all the multi-extruder infrastructure will be removed. +// Saves at least 800B of code size +//#ifdef __AVR__ +//static_assert(EXTRUDERS == 1); +//#endif + +#define MMU2_NO_TOOL 99 + +MMU3::MMU3 mmu3; + +namespace MMU3 { + + template + void waitForHotendTargetTemp(uint16_t delay, F f) { + while (((thermal_degTargetHotend() - thermal_degHotend()) > 5)) { + f(); + safe_delay_keep_alive(delay); + } + } + + void WaitForHotendTargetTempBeep() { + waitForHotendTargetTemp(3000, []{}); + //MakeSound(Prompt); + } + + uint8_t MMU3::cutter_mode; // Initialized by settings.load + int MMU3::cutter_mode_addr; // Initialized by settings.load + uint8_t MMU3::stealth_mode; // Initialized by settings.load + int MMU3::stealth_mode_addr; // Initialized by settings.load + // TODO: Currently, by logic, the value stored in the EEPROM for is ignored and + // mmu_hw_enabled is always overwritten by the MMU State. Thus restarting + // printer will always set the MMU as senabled. + bool MMU3::mmu_hw_enabled; // Initialized by settings.load + int MMU3::mmu_hw_enabled_addr; // Initialized by settings.load + + MMU3::MMU3() + : logic(MMU3_TOOL_CHANGE_LOAD_LENGTH, MMU3_LOAD_TO_NOZZLE_FEED_RATE) + , extruder(MMU2_NO_TOOL) + , tool_change_extruder(MMU2_NO_TOOL) + , resume_position() + , resume_hotend_temp(0) + , logicStepLastStatus(StepStatus::Finished) + , _state(xState::Stopped) + , mmu_print_saved(SavedState::None) + , loadFilamentStarted(false) + , unloadFilamentStarted(false) + , toolchange_counter(0) + , _tmcFailures(0) { } + + void MMU3::status() { + // Useful information to see during bootup and change state + SERIAL_ECHOLN(F("MMU is "), mmu_hw_enabled ? GET_TEXT_F(MSG_ON) : GET_TEXT_F(MSG_OFF)); + } + + void MMU3::start() { + mmu_hw_enabled = true; + + #if ENABLED(EEPROM_SETTINGS) + // Save mmu_hw_enabled to EEPROM + // TODO: Move to settings.cpp (for now) + persistentStore.access_start(); + persistentStore.write_data(mmu_hw_enabled_addr, mmu_hw_enabled); + persistentStore.access_finish(); + settings.save(); + #endif + + MMU_SERIAL.begin(MMU_BAUD); + + powerOn(); + MMU_SERIAL.flush(); // Make sure the UART buffer is clear before starting communication + + setCurrentTool(MMU2_NO_TOOL); + _state = xState::Connecting; + + // Start communication + logic.start(); + logic.ResetRetryAttempts(); + logic.ResetCommunicationTimeoutAttempts(); + } + + void MMU3::stop() { + stopKeepPowered(); + powerOff(); + } + + void MMU3::stopKeepPowered() { + mmu_hw_enabled = false; + + #if ENABLED(EEPROM_SETTINGS) + // Save mmu_hw_enabled to EEPROM + persistentStore.access_start(); + persistentStore.write_data(mmu_hw_enabled_addr, mmu_hw_enabled); + persistentStore.access_finish(); + settings.save(); + #endif + + _state = xState::Stopped; + logic.stop(); + MMU_SERIAL.end(); + } + + void MMU3::tune() { + switch (lastErrorCode) { + case ErrorCode::HOMING_SELECTOR_FAILED: + case ErrorCode::HOMING_IDLER_FAILED: { + // Prompt a menu for different values + tuneIdlerStallguardThreshold(); + break; + } + default: break; + } + } + + void MMU3::reset(ResetForm level) { + switch (level) { + case Software: resetX0(); break; + case ResetPin: triggerResetPin(); break; + case CutThePower: powerCycle(); break; + case EraseEEPROM: resetX42(); break; + default: break; + } + } + + void MMU3::resetX0() { logic.ResetMMU(); } // Send soft reset + void MMU3::resetX42() { logic.ResetMMU(42); } + + void MMU3::triggerResetPin() { power_reset(); } + + void MMU3::powerCycle() { + // cut the power to the MMU and after a while restore it + // Sadly, MK3/S/+ cannot do this + stop(); + safe_delay_keep_alive(1000); + start(); + } + + void MMU3::powerOff() { power_off(); } + void MMU3::powerOn() { power_on(); } + + bool MMU3::readRegister(uint8_t address) { + if (!waitForMMUReady()) return false; + + do { + logic.readRegister(address); // we may signal the accepted/rejected status of the response as return value of this function + } while (!manage_response(false, false)); + + // Update cached value + lastReadRegisterValue = logic.rsp.paramValue; + return true; + } + + bool __attribute__((noinline)) MMU3::writeRegister(uint8_t address, uint16_t data) { + if (!waitForMMUReady()) return false; + + // special cases - intercept requests of registers which influence the printer's behaviour too + perform the change even on the printer's side + switch (address) { + case (uint8_t)Register::Extra_Load_Distance: logic.PlanExtraLoadDistance(data); break; + case (uint8_t)Register::Pulley_Slow_Feedrate: logic.PlanPulleySlowFeedRate(data); break; + default: break; // Don't intercept any other register writes + } + + do { + logic.writeRegister(address, data); // we may signal the accepted/rejected status of the response as return value of this function + } while (!manage_response(false, false)); + + return true; + } + + void MMU3::mmu_loop() { + // We only leave this method if the current command was successfully + // completed - that's the Marlin's way of blocking operation + // Atomic compare_exchange would have been the most appropriate solution + // here, but this gets called only in Marlin's task, so thread safety + // should be kept + static bool avoidRecursion = false; + if (avoidRecursion) return; + avoidRecursion = true; + + mmu_loop_inner(true); + + avoidRecursion = false; + } + + void __attribute__((noinline)) MMU3::mmu_loop_inner(bool reportErrors) { + logicStepLastStatus = logicStep(reportErrors); // it looks like the mmu_loop doesn't need to be a blocking call + CheckErrorScreenUserInput(); + } + + /** + * Check if there are extruder moves planned ahead. + * + * TODO: This should go to the planner, but for now keep it here! + */ + bool MMU3::e_active() { + unsigned char e_active = 0; + block_t *block; + if (planner.block_buffer_tail != planner.block_buffer_head) { + uint8_t block_index = planner.block_buffer_tail; + while (block_index != planner.block_buffer_head) { + block = &planner.block_buffer[block_index]; + if (block->steps.e != 0) e_active++; + block_index = (block_index + 1) & (BLOCK_BUFFER_SIZE - 1); + } + } + return (e_active > 0); + } + + /** + * Trigger an M600 or the SpoolJoin feature if the FINDA cannot detect any + * filament during the print. + * + * In case of SpoolJoin feature is triggered, Marlin's implementation is a + * little different than Prusa's, as we are completely consuming the filament + * before switching to the next slot. There will be a little bit of filament + * left when the new filament is extruded SpoolJoin is not intended to be used with + * multi color/material prints so this should be fine. + */ + void MMU3::checkFINDARunout() { + if (!findaDetectsFilament() + //&& marlin.printJobOngoing() + && parser.codenum != 600 + && TERN1(HAS_LEVELING, planner.leveling_active) + && xy_are_trusted() + && e_active() + #if ENABLED(MMU3_SPOOL_JOIN_CONSUMES_ALL_FILAMENT) + && runout.enabled // to prevent M600 to be triggered during M600 AUTO + && !FILAMENT_PRESENT() // so the filament is totally consumed + #endif + ) { + SERIAL_ECHOLN_P("FINDA filament runout!"); + if (spooljoin.isEnabled() && get_current_tool() != (uint8_t)FILAMENT_UNKNOWN) { // Can't auto if F=? + #if ENABLED(MMU3_SPOOL_JOIN_CONSUMES_ALL_FILAMENT) + // set the current tool to FILAMENT_UNKNOWN so that we don't try to unload it + extruder = MMU2_NO_TOOL; + // disable the filament runout sensor (this is going to be re-enabled after the filament is loaded) + runout.reset(); + runout.filament_ran_out = false; // trying to disable the purge more / continue message + runout.enabled = false; + #endif + queue.enqueue_now(F("M600A")); // Save print and run M600 A (automatic) command + } + else { + marlin_stop_and_save_print_to_ram(); + resume_print(); + queue.enqueue_now(F("M600")); // Save print and run M600 command + } + } + } + + struct ReportingRAII { + CommandInProgress cip; + explicit inline __attribute__((always_inline)) ReportingRAII(CommandInProgress cip) + : cip(cip) { + BeginReport(cip, ProgressCode::EngagingIdler); + } + inline __attribute__((always_inline)) ~ReportingRAII() { + EndReport(cip, ProgressCode::OK); + } + }; + + bool MMU3::waitForMMUReady() { + switch (state()) { + case xState::Stopped: return false; + case xState::Connecting: + // Should we wait until the MMU reconnects? + // Fire up a fsm_dlg and show "MMU not responding"? + default: return true; + } + } + + bool MMU3::retryIfPossible(const ErrorCode ec) { + if (logic.RetryAttempts()) { + SetButtonResponse(ButtonOperations::Retry); + // check, that Retry is actually allowed on that operation + if (ButtonAvailable(ec) != Buttons::NoButton) { + logic.SetInAutoRetry(true); + SERIAL_ECHOLN_P("RetryButtonPressed"); + // We don't decrement until the button is acknowledged by the MMU. + // --retryAttempts; // "used" one retry attempt + return true; + } + } + logic.SetInAutoRetry(false); + return false; + } + + bool MMU3::verifyFilamentEnteredPTFE() { + planner_synchronize(); + + if (WhereIsFilament() != FilamentState::AT_FSENSOR) + return false; + + // MMU has finished its load, push the filament further by some defined constant length + // If the filament sensor reads 0 at any moment, then report FAILURE + const float tryload_length = MMU3_CHECK_FILAMENT_PRESENCE_EXTRUSION_LENGTH - logic.ExtraLoadDistance(); + TryLoadUnloadReporter tlur(tryload_length); + + /** + * The position is a triangle wave. + * Current position is not zero, it is an offset + * + * Keep in mind that the relationship between machine position + * and pixel index is not linear. The area around the amplitude + * needs to be taken care of carefully. The current implementation + * handles each move separately so there is no need to watch for the change + * in the slope's sign or check the last machine position. + * y(x) + * â–² + * │ ^◄────────── tryload_length + current_position + * machine │ / \ + * position │ / \◄────────── stepper_position_mm + current_position + * (mm) │ / \ + * │ / \ + * │/ \◄───────current_position + * └──────────────► x + * 0 19 + * pixel # + */ + + bool filament_inserted = true; // Expect success + // Pixel index will go from 0 to 10, then back from 10 to 0. + // A change in this value indicates a new pixel should be drawn on the display. + for (uint8_t move = 0; move < 2; move++) { + extruder_move(move == 0 ? tryload_length : -tryload_length, MMU3_VERIFY_LOAD_TO_NOZZLE_FEED_RATE); + while (planner_any_moves()) { + filament_inserted = filament_inserted && (WhereIsFilament() == FilamentState::AT_FSENSOR); + tlur.Progress(filament_inserted); + safe_delay_keep_alive(0); + } + } + Disable_E0(); + if (!filament_inserted) IncrementLoadFails(); + tlur.DumpToSerial(); + return filament_inserted; + } + + bool MMU3::toolChangeCommonOnce(uint8_t slot) { + static_assert(MMU3_MAX_RETRIES > 1); // Need >1 retries to do the cut in the last attempt + uint8_t retries = 0; + for (;;) { + for (;;) { + Disable_E0(); // It may seem counterintuitive to disable the E-motor, but it gets enabled in the planner whenever the E-motor is to move + tool_change_extruder = slot; + logic.ToolChange(slot); // Let the MMU pull the filament out and push a new one in + + if (manage_response(true, true)) break; + + // Otherwise: failed to perform the command - unload first and then let it run again + IncrementMMUFails(); + + // Just in case we stood in an error screen for too long and the hotend got cold + resumeHotendTemp(); + // If the extruder has been parked, it will get unparked once the ToolChange command finishes OK + // - so no resumeUnpark() at this spot + + unloadInner(); + // If we run out of retries, we must do something ... maybe raise an error screen and allow the user to do something. + // But honestly - if the MMU restarts during every toolchange something else is seriously broken + // and stopping a print is probably our best option. + } + if (verifyFilamentEnteredPTFE()) return true; // success + + // Prepare a retry attempt + unloadInner(); + if (retries == (MMU3_MAX_RETRIES) - 1 && cutter_enabled()) { + cutFilamentInner(slot); // try cutting filament tip at the last attempt + retries = 0; // reset retries every MMU3_MAX_RETRIES + } + + ++retries; + } + return false; // Couldn't accomplish the task + } + + void MMU3::toolChangeCommon(uint8_t slot) { + while (!toolChangeCommonOnce(slot)) { // While not successfully fed into extruder's PTFE tube... + // Failed autoretry, report an error by forcing a "printer" error into the MMU infrastructure - it is a hack to leverage existing code + // @@TODO theoretically logic layer may not need to be spoiled with the printer error - maybe just the manage_response needs it... + logic.SetPrinterError(ErrorCode::LOAD_TO_EXTRUDER_FAILED); + // We only have to wait for the user to fix the issue and press "Retry". + // Please see checkUserInput() for details how we "leave" manage_response. + // If manage_response returns false at this spot (MMU operation interrupted aka MMU reset) + // we can safely continue because the MMU is not doing an operation now. + static_cast(manage_response(true, true)); // yes, I'd like to silence [[nodiscard]] warning at this spot by casting to void + } + + setCurrentTool(slot); // filament change is finished + spooljoin.setSlot(slot); + + ++toolchange_counter; + + // Also increment the total number of tool changes + operation_statistics.increment_tool_change_counter(); + } + + bool MMU3::tool_change(uint8_t slot) { + if (!waitForMMUReady()) return false; + + if (slot != extruder) { + if ( + //findaDetectsFilament() + //!card.isStillPrinting() && !usb_timer.running() + !marlin_printingIsActive() + ) { + // If Tcodes are used manually through the serial + // we need to unload manually as well -- but only if FINDA detects filament + unload(); + } + + ReportingRAII rep(CommandInProgress::ToolChange); + FSensorBlockRunout blockRunout; + planner_synchronize(); + toolChangeCommon(slot); + } + return true; + } + + /** + * Handle special T?/Tx/Tc commands + * + * - T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically + * - Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. + * - Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. + */ + bool MMU3::tool_change(char code, uint8_t slot) { + if (!waitForMMUReady()) return false; + + FSensorBlockRunout blockRunout; + + switch (code) { + case '?': { + waitForHotendTargetTemp(100, []{}); + load_to_nozzle(slot); + } + break; + + case 'x': { + thermal_setExtrudeMintemp(0); // Allow cold extrusion since Tx only loads to the gears not nozzle + tool_change(slot); + thermal_setExtrudeMintemp(EXTRUDE_MINTEMP); + } + break; + + case 'c': { + waitForHotendTargetTemp(100, []{}); + execute_load_to_nozzle_sequence(); + } + break; + } + + return true; + } + + void MMU3::get_statistics() { + logic.Statistics(); + } + + uint8_t __attribute__((noinline)) MMU3::get_current_tool() const { + return extruder == MMU2_NO_TOOL ? (uint8_t)FILAMENT_UNKNOWN : extruder; + } + + uint8_t MMU3::get_tool_change_tool() const { + return tool_change_extruder == MMU2_NO_TOOL ? (uint8_t)FILAMENT_UNKNOWN : tool_change_extruder; + } + + void MMU3::setCurrentTool(uint8_t ex) { + extruder = ex; + MMU2_ECHO_MSGRPGM(PSTR("MMU2tool=")); + SERIAL_ECHOLN((int)ex); + } + + bool MMU3::set_filament_type(uint8_t /*slot*/, uint8_t /*type*/) { + if (!waitForMMUReady()) return false; + + // @@TODO - this is not supported in the new MMU yet + // slot = slot; // @@TODO + // type = type; // @@TODO + // cmd_arg = filamentType; + // command(MMU_CMD_F0 + index); + + if (!manage_response(false, false)) { + // @@TODO failed to perform the command - retry + // Comment: how is it possible for a filament type set to fail? manage_response(true, true) + } + + return true; + } + + void MMU3::unloadInner() { + FSensorBlockRunout blockRunout; + filament_ramming(); + + // we assume the printer managed to relieve filament tip from the gears, + // so repeating that part in case of an MMU restart is not necessary + for (;;) { + Disable_E0(); + logic.UnloadFilament(); + if (manage_response(false, true)) break; + IncrementMMUFails(); + } + //MakeSound(Confirm); + + // no active tool + setCurrentTool(MMU2_NO_TOOL); + tool_change_extruder = MMU2_NO_TOOL; + } + + bool MMU3::unload() { + if (!waitForMMUReady()) return false; + + WaitForHotendTargetTempBeep(); + + // Scope for ReportingRAII + { + ReportingRAII rep(CommandInProgress::UnloadFilament); + unloadInner(); + } + + ScreenUpdateEnable(); + return true; + } + + void MMU3::cutFilamentInner(uint8_t slot) { + for (;;) { + Disable_E0(); + logic.CutFilament(slot); + if (manage_response(false, true)) break; + IncrementMMUFails(); + } + } + + bool MMU3::cut_filament(uint8_t slot, bool enableFullScreenMsg /*= true*/) { + if (!waitForMMUReady()) return false; + + if (enableFullScreenMsg) fullScreenMsgCut(slot); + + // Scope for ReportingRAII + { + if (findaDetectsFilament()) unload(); + + ReportingRAII rep(CommandInProgress::CutFilament); + cutFilamentInner(slot); + setCurrentTool(MMU2_NO_TOOL); + tool_change_extruder = MMU2_NO_TOOL; + //MakeSound(SoundType::Confirm); + } + ScreenUpdateEnable(); + return true; + } + + bool MMU3::loading_test(uint8_t slot) { + fullScreenMsgTest(slot); + tool_change(slot); + planner_synchronize(); + unload(); + ScreenUpdateEnable(); + return true; + } + + bool MMU3::load_to_feeder(uint8_t slot) { + if (!waitForMMUReady()) return false; + + fullScreenMsgLoad(slot); + + // Scope for ReportingRAII + { + ReportingRAII rep(CommandInProgress::LoadFilament); + for (;;) { + Disable_E0(); + logic.LoadFilament(slot); + if (manage_response(false, false)) break; + IncrementMMUFails(); + } + //MakeSound(SoundType::Confirm); + } + ScreenUpdateEnable(); + return true; + } + + bool MMU3::load_to_nozzle(uint8_t slot) { + if (!waitForMMUReady()) return false; + + WaitForHotendTargetTempBeep(); + + fullScreenMsgLoad(slot); + + // Scope for ReportingRAII + { + // Used for MMU-menu operation "Load to Nozzle" + ReportingRAII rep(CommandInProgress::ToolChange); + FSensorBlockRunout blockRunout; + + // Filament already loaded? Free it and shape its tip properly. + if (extruder != MMU2_NO_TOOL) filament_ramming(); + + toolChangeCommon(slot); + + // Finish loading to the nozzle with finely tuned steps. + execute_load_to_nozzle_sequence(); + //MakeSound(Confirm); + } + ScreenUpdateEnable(); + return true; + } + + bool MMU3::eject_filament(uint8_t slot, bool enableFullScreenMsg /* = true */) { + if (!waitForMMUReady()) return false; + + if (enableFullScreenMsg) fullScreenMsgEject(slot); + + // Scope for ReportingRAII + { + if (findaDetectsFilament()) + unload(); + + ReportingRAII rep(CommandInProgress::EjectFilament); + for (;;) { + Disable_E0(); + logic.EjectFilament(slot); + if (manage_response(false, true)) + break; + IncrementMMUFails(); + } + setCurrentTool(MMU2_NO_TOOL); + tool_change_extruder = MMU2_NO_TOOL; + //MakeSound(Confirm); + } + ScreenUpdateEnable(); + return true; + } + + void MMU3::button(uint8_t index) { + LogEchoEvent(F("button")); + logic.button(index); + } + + void MMU3::home(uint8_t mode) { + logic.home(mode); + } + + void MMU3::saveHotendTemp(bool turn_off_nozzle) { + if (mmu_print_saved & SavedState::Cooldown) return; + + if (turn_off_nozzle && !(mmu_print_saved & SavedState::CooldownPending)) { + Disable_E0(); + resume_hotend_temp = thermal_degTargetHotend(); + mmu_print_saved |= SavedState::CooldownPending; + LogEchoEvent(F("Heater cooldown pending")); + } + } + + void MMU3::saveAndPark(bool move_axes) { + if (mmu_print_saved == SavedState::None) { // First occurrence. Save current position, park print head, disable nozzle heater. + LogEchoEvent(F("Saving and parking")); + Disable_E0(); + planner_synchronize(); + + // In case a power panic happens while waiting for the user + // take a partial back up of print state into RAM (current position, etc.) + marlin_refresh_print_state_in_ram(); + + if (move_axes) { + mmu_print_saved |= SavedState::ParkExtruder; + resume_position = planner_current_position(); // save current pos + + // Do not lift Z, as it will double lift if there is another error + // right after the current one is solved. + + // Move XY aside + if (xy_are_trusted()) nozzle_park(); + } + } + } + + void MMU3::resumeHotendTemp() { + if ((mmu_print_saved & SavedState::CooldownPending)) { + // Clear the "pending" flag if we haven't cooled yet. + mmu_print_saved &= ~(SavedState::CooldownPending); + LogEchoEvent(F("Cooldown flag cleared")); + } + if ((mmu_print_saved & SavedState::Cooldown) && resume_hotend_temp) { + LogEchoEvent(F("Resuming Temp")); + // @@TODO MMU2_ECHO_MSGRPGM(PSTR("Restoring hotend temperature ")); + SERIAL_ECHOLN(resume_hotend_temp); + mmu_print_saved &= ~(SavedState::Cooldown); + thermal_setTargetHotend(resume_hotend_temp); + fullScreenMsgRestoringTemperature(); + // @todo better report the event and let the GUI do its work somewhere else + ReportErrorHookSensorLineRender(); + waitForHotendTargetTemp(100, [] { + marlin_manage_inactivity(true); + mmu3.mmu_loop_inner(false); + ReportErrorHookDynamicRender(); + }); + ScreenUpdateEnable(); // temporary hack to stop this locking the printer... + LogEchoEvent(F("Hotend temperature reached")); + ScreenClear(); + } + } + + void MMU3::resumeUnpark() { + if (mmu_print_saved & SavedState::ParkExtruder) { + LogEchoEvent(F("Resuming XYZ")); + + // Move XY to starting position, then Z + motion_blocking_move_xy(resume_position.x, resume_position.y, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); + + // Move Z_AXIS to saved position + motion_blocking_move_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + + // From this point forward, power panic should not use + // the partial backup in RAM since the extruder is no + // longer in parking position + marlin_clear_print_state_in_ram(); + + mmu_print_saved &= ~(SavedState::ParkExtruder); + } + } + + void MMU3::checkUserInput() { + auto btn = ButtonPressed(lastErrorCode); + + // Was a button pressed on the MMU itself instead of the LCD? + if (btn == Buttons::NoButton && lastButton != Buttons::NoButton) { + btn = lastButton; + lastButton = Buttons::NoButton; // Clear it. + } + + if (mmuLastErrorSource() == MMU3::ErrorSourcePrinter && btn != Buttons::NoButton) { + // When the printer has raised an error screen, and a button was selected + // the error screen should always be dismissed. + clearPrinterError(); + // A horrible hack - clear the explicit printer error allowing manage_response to recover on MMU's Finished state + // Moreover - if the MMU is currently doing something (like the LoadFilament - see comment above) + // we'll actually wait for it automagically in manage_response and after it finishes correctly, + // we'll issue another command (like toolchange) + } + + switch (btn) { + case Buttons::Left: + case Buttons::Middle: + case Buttons::Right: + SERIAL_ECHOPGM("checkUserInput-btnLMR "); + SERIAL_ECHOLN((int)buttons_to_uint8t(btn)); + resumeHotendTemp(); // Recover the hotend temp before we attempt to do anything else... + + if (mmuLastErrorSource() == MMU3::ErrorSourceMMU) + // Do not send a button to the MMU unless the MMU is in error state + button(buttons_to_uint8t(btn)); + + // A quick hack: for specific error codes move the E-motor every time. + // Not sure if we can rely on the fsensor. + // Just plan the move, let the MMU take over when it is ready + switch (lastErrorCode) { + case ErrorCode::FSENSOR_DIDNT_SWITCH_OFF: + case ErrorCode::FSENSOR_TOO_EARLY: helpUnloadToFinda(); break; + default: break; + } + break; + case Buttons::TuneMMU: + tune(); + break; + case Buttons::Load: + case Buttons::Eject: + // High level operation + setPrinterButtonOperation(btn); + break; + case Buttons::ResetMMU: + reset(ResetPin); // Cannot do power cycle on the MK3 + // ... but mmu2_power.cpp knows this and triggers a soft-reset instead. + break; + case Buttons::DisableMMU: + stop(); + //DisableMMUInSettings(); // stop() already does this... + status(); + break; + case Buttons::StopPrint: + // @@TODO Unsure if we should handle this high level operation at this spot + break; + default: break; + } + } + + /** + * Originally, this was used to wait for response and deal with timeout if necessary. + * The new protocol implementation enables much nicer and intense reporting, so this method will boil down + * just to verify the result of an issued command (which was basically the original idea) + * + * It is closely related to mmu_loop() (which corresponds to our ProtocolLogic::Step()), which does NOT perform any blocking wait for a command to finish. + * But - in case of an error, the command is not yet finished, but we must react accordingly - move the printhead elsewhere, stop heating, eat a cat or so. + * That's what's being done here... + */ + bool MMU3::manage_response(const bool move_axes, const bool turn_off_nozzle) { + mmu_print_saved = SavedState::None; + + MARLIN_KEEPALIVE_STATE_IN_PROCESS; + + Stopwatch nozzle_timer; + + for (;;) { + // in our new implementation, we know the exact state of the MMU at any moment, we do not have to wait for a timeout + // So in this case we should decide if the operation is: + // - still running -> wait normally in marlin.idle() + // - failed -> then do the safety moves on the printer like before + // - finished ok -> proceed with reading other commands + safe_delay_keep_alive(0); // calls logicStep() and remembers its return status + + if (mmu_print_saved & SavedState::CooldownPending) { + if (!nozzle_timer.isRunning()) { + nozzle_timer.start(); + LogEchoEvent(F("Cooling Timeout started")); + } + else if (nozzle_timer.duration() > (PAUSE_PARK_NOZZLE_TIMEOUT * 1000UL)) { // mins->msec. + mmu_print_saved &= ~(SavedState::CooldownPending); + mmu_print_saved |= SavedState::Cooldown; + thermal_setTargetHotend(0); + LogEchoEvent(F("Heater cooldown")); + } + } + else if (nozzle_timer.isRunning()) { + nozzle_timer.stop(); + LogEchoEvent(F("Cooling timer stopped")); + } + + switch (logicStepLastStatus) { + case Finished: + // command/operation completed, let Marlin continue its work + // the E may have some more moves to finish - wait for them + resumeHotendTemp(); + resumeUnpark(); // We can now travel back to the tower or wherever we were when we saved. + if (!TuneMenuEntered()) { + // If the error screen is sleeping (running 'Tune' menu) + // then don't reset retry attempts because we this will trigger + // an automatic retry attempt when 'Tune' button is selected. We want the + // error screen to appear once more so the user can hit 'Retry' button manually. + logic.ResetRetryAttempts(); // Reset the retry counter. + } + planner_synchronize(); + return true; + case Interrupted: + // now what :D ... big bad ... ramming, unload, retry the whole command originally issued + return false; + case VersionMismatch: // this basically means the MMU will be disabled until reconnected + checkUserInput(); + return true; + case PrinterError: + saveAndPark(move_axes); + saveHotendTemp(turn_off_nozzle); + checkUserInput(); + // if button pressed "Done", return true, otherwise stay within manage_response + // Please see checkUserInput() for details how we "leave" manage_response + break; + case CommandError: + case CommunicationTimeout: + case ProtocolError: + case ButtonPushed: + if (!logic.InAutoRetry()) { + // Don't proceed to the park/save if we are doing an autoretry. + saveAndPark(move_axes); + saveHotendTemp(turn_off_nozzle); + checkUserInput(); + } + break; + case CommunicationRecovered: // @@TODO communication recovered and maybe an error recovered as well + // Maybe the logic layer can detect the change of state a respond with one "Recovered" to be handled here + resumeHotendTemp(); + resumeUnpark(); + break; + case Processing: // Wait for the MMU to respond + default: break; + } + } + } + + StepStatus MMU3::logicStep(bool reportErrors) { + // Process any buttons before proceeding with another MMU Query + checkUserInput(); + + const StepStatus ss = logic.Step(); + switch (ss) { + + case Finished: + // At this point it is safe to trigger a runout and not interrupt the MMU protocol + checkFINDARunout(); + break; + + case Processing: + onMMUProgressMsg(logic.Progress()); + break; + + case ButtonPushed: + lastButton = logic.button(); + LogEchoEvent(F("MMU button pushed")); + checkUserInput(); // Process the button immediately + break; + + case Interrupted: + // can be silently handed over to a higher layer, no processing necessary at this spot + break; + + default: + if (reportErrors) { + switch (ss) { + + case CommandError: + reportError(logic.Error(), ErrorSourceMMU); + break; + + case CommunicationTimeout: + _state = xState::Connecting; + reportError(ErrorCode::MMU_NOT_RESPONDING, ErrorSourcePrinter); + break; + + case ProtocolError: + _state = xState::Connecting; + reportError(ErrorCode::PROTOCOL_ERROR, ErrorSourcePrinter); + break; + + case VersionMismatch: + stopKeepPowered(); + reportError(ErrorCode::VERSION_MISMATCH, ErrorSourcePrinter); + break; + + case PrinterError: + reportError(logic.PrinterError(), ErrorSourcePrinter); + break; + + default: + break; + } + } + } + + if (logic.Running()) _state = xState::Active; + + return ss; + } + + void MMU3::filament_ramming() { + execute_extruder_sequence(ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step)); + } + + void MMU3::execute_extruder_sequence(const E_Step *sequence, uint8_t steps) { + planner_synchronize(); + + const E_Step *step = sequence; + for (uint8_t i = steps; i > 0; --i) { + extruder_move(pgm_read_float(&(step->extrude)), pgm_read_float(&(step->feedRate))); + step++; + } + planner_synchronize(); // it looks like it's better to sync the moves at the end - smoother move (if the sequence is not too long). + + Disable_E0(); + } + + void MMU3::execute_load_to_nozzle_sequence() { + planner_synchronize(); + // Compensate for configurable Extra Loading Distance + planner_set_current_position_E(planner_get_current_position_E() - (logic.ExtraLoadDistance() - MMU3_FILAMENT_SENSOR_E_POSITION)); + execute_extruder_sequence(load_to_nozzle_sequence, sizeof(load_to_nozzle_sequence) / sizeof(load_to_nozzle_sequence[0])); + } + + void MMU3::reportError(ErrorCode ec, ErrorSource res) { + // Due to a potential lossy error reporting layers linked to this hook + // we'd better report everything to make sure especially the error states + // do not get lost. + // - The good news here is the fact, that the MMU reports the errors repeatedly until resolved. + // - The bad news is, that MMU not responding may repeatedly occur on printers not having the MMU at all. + // + // Not sure how to properly handle this situation, options: + // - skip reporting "MMU not responding" (at least for now) + // - report only changes of states (we can miss an error message) + // - maybe some combination of MMUAvailable + UseMMU flags and decide based on their state + // Right now the filtering of MMU_NOT_RESPONDING is done in ReportErrorHook() as it is not a problem if mmu2.cpp + + // Depending on the Progress code, we may want to do some action when an error occurs + switch (logic.Progress()) { + case ProgressCode::UnloadingToFinda: + unloadFilamentStarted = false; + planner_abort_queued_moves(); // Abort excess E-moves to be safe + break; + case ProgressCode::FeedingToFSensor: + // FSENSOR error during load. Make sure E-motor stops moving. + loadFilamentStarted = false; + planner_abort_queued_moves(); // Abort excess E-moves to be safe + break; + default: break; + } + + if (ec != lastErrorCode) { // deduplicate: only report changes in error codes into the log + lastErrorCode = ec; + lastErrorSource = res; + LogErrorEvent(PrusaErrorTitle(PrusaErrorCodeIndex(ec))); + + if (ec != ErrorCode::OK && ec != ErrorCode::FILAMENT_EJECTED && ec != ErrorCode::FILAMENT_CHANGE) { + IncrementMMUFails(); + + // Check if it is a "power" failure. TMC-related errors are considered power failures. + static constexpr uint16_t tmcMask = + ( (uint16_t)ErrorCode::TMC_IOIN_MISMATCH + | (uint16_t)ErrorCode::TMC_RESET + | (uint16_t)ErrorCode::TMC_UNDERVOLTAGE_ON_CHARGE_PUMP + | (uint16_t)ErrorCode::TMC_SHORT_TO_GROUND + | (uint16_t)ErrorCode::TMC_OVER_TEMPERATURE_WARN + | (uint16_t)ErrorCode::TMC_OVER_TEMPERATURE_ERROR + | (uint16_t)ErrorCode::MMU_SOLDERING_NEEDS_ATTENTION ) & 0x7FFFU; // skip the top bit + + static_assert(tmcMask == 0x7E00); // Just make sure we fail compilation if any of the TMC error codes change + + if ((uint16_t)ec & tmcMask) { // @@TODO can be optimized to uint8_t operation + // TMC-related errors are from 0x8200 higher + incrementTMCFailures(); + } + } + } + + if (!retryIfPossible(ec)) + // If retry attempts are all used up + // or if 'Retry' operation is not available + // raise the MMU error screen and wait for user input + ReportErrorHook((CommandInProgress)logic.CommandInProgress(), ec, uint8_t(lastErrorSource)); + } + + void MMU3::reportProgress(ProgressCode pc) { + ReportProgressHook((CommandInProgress)logic.CommandInProgress(), pc); + LogEchoEvent(ProgressCodeToText(pc)); + } + + void MMU3::onMMUProgressMsg(ProgressCode pc) { + if (pc != lastProgressCode) + onMMUProgressMsgChanged(pc); + else + onMMUProgressMsgSame(pc); + } + + void MMU3::onMMUProgressMsgChanged(ProgressCode pc) { + reportProgress(pc); + lastProgressCode = pc; + switch (pc) { + case ProgressCode::UnloadingToFinda: + if ( (CommandInProgress)logic.CommandInProgress() == CommandInProgress::UnloadFilament + || ((CommandInProgress)logic.CommandInProgress() == CommandInProgress::ToolChange) + ) { + // If MK3S sent U0 command, ramming sequence takes care of releasing the filament. + // If Toolchange is done while printing, PrusaSlicer takes care of releasing the filament + // If printing is not in progress, ToolChange will issue a U0 command. + break; + } + else { + // We're likely recovering from an MMU error + planner_synchronize(); + unloadFilamentStarted = true; + helpUnloadToFinda(); + } + break; + case ProgressCode::FeedingToFSensor: + // prepare for the movement of the E-motor + planner_synchronize(); + loadFilamentStarted = true; + break; + default: break; // do nothing yet + } + } + + void __attribute__((noinline)) MMU3::helpUnloadToFinda() { + extruder_move(-MMU3_RETRY_UNLOAD_TO_FINDA_LENGTH, MMU3_RETRY_UNLOAD_TO_FINDA_FEED_RATE); + } + + void MMU3::onMMUProgressMsgSame(ProgressCode pc) { + const uint8_t pulley_slow_feedrate = logic.PulleySlowFeedRate(); + const float extrude_distance = _MIN(_MAX(EXTRUDE_MAXLENGTH - 1, 1), pulley_slow_feedrate); + + switch (pc) { + case ProgressCode::UnloadingToFinda: + if (unloadFilamentStarted && !planner_any_moves()) { // Only plan a move if there is no move ongoing + switch (WhereIsFilament()) { + case FilamentState::AT_FSENSOR: + case FilamentState::IN_NOZZLE: + case FilamentState::UNAVAILABLE: // actually Unavailable makes sense as well to start the E-move to release the filament from the gears + helpUnloadToFinda(); + break; + default: + unloadFilamentStarted = false; + } + } + break; + + case ProgressCode::FeedingToFSensor: + if (loadFilamentStarted) { + switch (WhereIsFilament()) { + case FilamentState::AT_FSENSOR: + // fsensor triggered, finish FeedingToExtruder state + loadFilamentStarted = false; + + // Abort any excess E-move from the planner queue + planner_abort_queued_moves(); + + // After the MMU knows the FSENSOR is triggered it will: + // 1. Push the filament by additional 30mm (see fsensorToNozzle) + // 2. Disengage the idler and push another 2mm. + extruder_move(logic.ExtraLoadDistance() + 2, logic.PulleySlowFeedRate()); + break; + case FilamentState::NOT_PRESENT: + // fsensor not triggered, continue moving extruder + // + // Instead of doing a very long extrude as in PrusaFirmware, + // Marlin's own MMU2s code has a better approach to this by spinning + // the extruder indefinitely... + // + // this ensures that while the MMU is pushing the filament, + // the extruder will keep rotating, preventing the filament to hit + // the extruder gears... + while (planner.movesplanned() < 3) { + extruder_move(extrude_distance, pulley_slow_feedrate, false); + } + break; + default: break; // Abort here? + } + } + break; + + default: break; // do nothing yet + } + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3.h b/Marlin/src/feature/mmu3/mmu3.h new file mode 100644 index 0000000000..968f76a912 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3.h @@ -0,0 +1,419 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2.h + */ + +#include "mmu3_state.h" +#include "mmu3_marlin.h" + +#include "mmu3_protocol_logic.h" + +#include "../../MarlinCore.h" + + #ifdef __AVR__ + typedef float feedRate_t; + #else + //#include + #endif + + struct E_Step { + float extrude; //!< extrude distance in mm + float feedRate; //!< feed rate in mm/s + }; + + static constexpr E_Step ramming_sequence[] PROGMEM = { MMU3_RAMMING_SEQUENCE }; + static constexpr E_Step load_to_nozzle_sequence[] PROGMEM = { MMU3_LOAD_TO_NOZZLE_SEQUENCE }; + + namespace MMU3 { + + // general MMU setup for MK3 + enum : uint8_t { + FILAMENT_UNKNOWN = 0xFFU + }; + + struct Version { + uint8_t major, minor, build; + }; + + // Top-level interface between Logic and Marlin. + // Intentionally named MMU3 to be (almost) a drop-in replacement for the previous implementation. + // Most of the public methods share the original naming convention as well. + class MMU3 { + public: + MMU3(); + + // Powers ON the MMU, then initializes the UART and protocol logic + void start(); + + // Stops the protocol logic, closes the UART, powers OFF the MMU + void stop(); + + // Serial output of MMU state + void status(); + + xState state() const { return _state; } + + bool enabled() const { mmu_hw_enabled = state() == xState::Active; return mmu_hw_enabled; } + + // Different levels of resetting the MMU + enum ResetForm : uint8_t { + Software = 0, //!< sends a X0 command into the MMU, the MMU will watchdog-reset itself + ResetPin = 1, //!< trigger the reset pin of the MMU + CutThePower = 2, //!< power off and power on (that includes +5V and +24V power lines) + EraseEEPROM = 42, //!< erase MMU EEPROM and then perform a software reset + }; + + // Saved print state on error. + enum SavedState : uint8_t { + None = 0, // No state saved. + ParkExtruder = 1, // The extruder was parked. + Cooldown = 2, // The extruder was allowed to cool. + CooldownPending = 4, + }; + + // Source of operation error + enum ErrorSource : uint8_t { + ErrorSourcePrinter = 0, + ErrorSourceMMU = 1, + ErrorSourceNone = 0xFF, + }; + + // Tune value in MMU registers as a way to recover from errors + // e.g. Idler Stallguard threshold + void tune(); + + // Perform a reset of the MMU + // @param level physical form of the reset + void reset(ResetForm level); + + // Power off the MMU (cut the power) + void powerOff(); + + // Power on the MMU + void powerOn(); + + // Read from a MMU register (See gcode M707) + // @param address Address of register in hexadecimal + // @return true upon success + bool readRegister(uint8_t address); + + // Write from a MMU register (See gcode M708) + // @param address Address of register in hexadecimal + // @param data Data to write to register + // @return true upon success + bool writeRegister(uint8_t address, uint16_t data); + + // The main loop of MMU processing. + // Doesn't loop (block) inside, performs just one step of logic state machines. + // Also, internally it prevents recursive entries. + void mmu_loop(); + + // The main MMU command - select a different slot + // @param slot of the slot to be selected + // @return false if the operation cannot be performed (Stopped) + bool tool_change(uint8_t slot); + + // Handling of special Tx, Tc, T? commands + bool tool_change(char code, uint8_t slot); + + // Unload of filament in collaboration with the MMU. + // That includes rotating the printer's extruder in order to release filament. + // @return false if the operation cannot be performed (Stopped or cold extruder) + bool unload(); + + // Load (insert) filament just into the MMU (not into printer's nozzle) + // @return false if the operation cannot be performed (Stopped) + bool load_to_feeder(uint8_t slot); + + // Load (push) filament from the MMU into the printer's nozzle + // @return false if the operation cannot be performed (Stopped or cold extruder) + bool load_to_nozzle(uint8_t slot); + + // Move MMU's selector aside and push the selected filament forward. + // Usable for improving filament's tip or pulling the remaining piece of filament out completely. + bool eject_filament(uint8_t slot, bool enableFullScreenMsg=true); + + // Issue a Cut command into the MMU + // Requires unloaded filament from the printer (obviously) + // @return false if the operation cannot be performed (Stopped) + bool cut_filament(uint8_t slot, bool enableFullScreenMsg=true); + + // Issue a planned request for statistics data from MMU + void get_statistics(); + + // Issue a Try-Load command + // It behaves very similarly like a ToolChange, but it doesn't load the filament + // all the way down to the nozzle. The sole purpose of this operation + // is to check, that the filament will be ready for printing. + // @param slot index of slot to be tested + // @return true + bool loading_test(uint8_t slot); + + // @return the active filament slot index (0-4) or 0xff in case of no active tool + uint8_t get_current_tool() const; + + // @return The filament slot index (0 to 4) that will be loaded next, 0xff in case of no active tool change + uint8_t get_tool_change_tool() const; + + bool set_filament_type(uint8_t slot, uint8_t type); + + // Issue a "button" click into the MMU - to be used from Error screens of the MMU + // to select one of the 3 possible options to resolve the issue + void button(uint8_t index); + + // Issue an explicit "homing" command into the MMU + void home(uint8_t mode); + + // @return current state of FINDA (true=filament present, false=filament not present) + bool findaDetectsFilament() const { return logic.findaPressed(); } + + uint16_t totalFailStatistics() const { return logic.FailStatistics(); } + + // @return Current error code + ErrorCode mmuCurrentErrorCode() const { return logic.Error(); } + + // @return Command in progress + uint8_t getCommandInProgress() const { return logic.CommandInProgress(); } + + // @return Last error source + ErrorSource mmuLastErrorSource() const { return lastErrorSource; } + + // @return Last error code + ErrorCode getLastErrorCode() const { return lastErrorCode; } + + // @return the version of the connected MMU FW. + // In the future we'll return the truly detected FW version + Version getMMUFWVersion() const { + if (state() == xState::Active) { + return { logic.mmuFwVersionMajor(), logic.mmuFwVersionMinor(), logic.mmuFwVersionRevision() }; + } + else { + return { 0, 0, 0 }; + } + } + + // Method to read-only mmu_print_saved + bool MMU_PRINT_SAVED() const { return mmu_print_saved != SavedState::None; } + + // Automagically "press" a Retry button if we have any retry attempts left + // @param ec ErrorCode enum value + // @return true if auto-retry is ongoing, false when retry is unavailable or retry attempts are all used up + bool retryIfPossible(const ErrorCode ec); + + // @return count for toolchange in current print + uint16_t toolChangeCounter() const { return toolchange_counter; } + + // Set toolchange counter to zero + void resetToolChangeCounter() { toolchange_counter = 0; } + + uint16_t tmcFailures() const { return _tmcFailures; } + void incrementTMCFailures() { ++_tmcFailures; } + void resetTMCFailures() { _tmcFailures = 0; } + + // Retrieve cached value parsed from readRegister() + // or using M707 + uint16_t getLastReadRegisterValue() const { + return lastReadRegisterValue; + } + void invokeErrorScreen(const ErrorCode ec) { + if (logic.CommandInProgress()) return; // MMU must not be busy + if (lastErrorCode == ec) return; // The error code is not a duplicate + if (mmuCurrentErrorCode() == ErrorCode::OK) { // The protocol must not be in error state + reportError(ec, ErrorSource::ErrorSourcePrinter); + } + } + + void clearPrinterError() { + logic.clearPrinterError(); + lastErrorCode = ErrorCode::OK; + lastErrorSource = ErrorSource::ErrorSourceNone; + } + + // @brief Queue a button operation which the printer can act upon + // @param btn Button operation + void setPrinterButtonOperation(Buttons btn) { + printerButtonOperation = btn; + } + + // @brief Get the printer button operation + // @return currently set printer button operation, it can be NoButton if nothing is queued + Buttons getPrinterButtonOperation() { + return printerButtonOperation; + } + + void clearPrinterButtonOperation() { + printerButtonOperation = Buttons::NoButton; + } + + static uint8_t cutter_mode; // mode 0:disabled | 1:enabled | 2:always (EXPERIMENTAL) + static int cutter_mode_addr; // EEPROM addr for cutter enabled setting + static uint8_t stealth_mode; // stealth mode + static int stealth_mode_addr; // EEPROM addr for stealth_mode setting + static bool mmu_hw_enabled; // MMU hardware can be Enabled/Disabled + // with the M709 S0 or M709 S1 commands + // and the last state is stored in the + // EEPROM + + static int mmu_hw_enabled_addr; // EEPROM addr for mmu_hw_enabled + + bool e_active(); + + #ifndef UNITTEST + private: + #endif + + // Perform software self-reset of the MMU (sends an X0 command) + void resetX0(); + + // Perform software self-reset of the MMU + erase its EEPROM (sends X2a command) + void resetX42(); + + // Trigger reset pin of the MMU + void triggerResetPin(); + + // Perform power cycle of the MMU (cold boot) + // Please note this is a blocking operation (sleeps for some time inside while doing the power cycle) + void powerCycle(); + + // Stop the communication, but keep the MMU powered on (for scenarios with incorrect FW version) + void stopKeepPowered(); + + // Along with the mmu_loop method, this loops until a response from the MMU is received and acts upon. + // In case of an error, it parks the print head and turns off nozzle heating + // @return false if the command could not have been completed (MMU interrupted) + [[nodiscard]] bool manage_response(const bool move_axes, const bool turn_off_nozzle); + + // The inner private implementation of mmu_loop() + // which is NOT (!!!) recursion-guarded. Use caution - but we do need it during waiting for hotend resume to keep comms alive! + // @param reportErrors true if Errors should raise MMU Error screen, false otherwise + void mmu_loop_inner(bool reportErrors); + + // Performs one step of the protocol logic state machine + // and reports progress and errors if needed to attached ExtUIs. + // Updates the global state of MMU (Active/Connecting/Stopped) at runtime, see @ref State + // @param reportErrors true if Errors should raise MMU Error screen, false otherwise + StepStatus logicStep(bool reportErrors); + + void filament_ramming(); + void execute_extruder_sequence(const E_Step *sequence, uint8_t steps); + void execute_load_to_nozzle_sequence(); + + // Reports an error into attached ExtUIs + // @param ec error code, see ErrorCode + // @param res reporter error source, is either Printer (0) or MMU (1) + void reportError(ErrorCode ec, ErrorSource res); + + // Reports progress of operations into attached ExtUIs + // @param pc progress code, see ProgressCode + void reportProgress(ProgressCode pc); + + // Responds to a change of MMU's progress + // - plans additional steps, e.g. starts the E-motor after fsensor trigger + // The function is quite complex, because it needs to handle asynchronnous + // progress and error reports coming from the MMU without an explicit command + // - typically after MMU's start or after some HW issue on the MMU. + // It must ensure, that calls to @ref reportProgress and/or @ref reportError are + // only executed after @ref BeginReport has been called first. + void onMMUProgressMsg(ProgressCode pc); + // Progress code changed - act accordingly + void onMMUProgressMsgChanged(ProgressCode pc); + // Repeated calls when progress code remains the same + void onMMUProgressMsgSame(ProgressCode pc); + + // @brief Save hotend temperature and set flag to cooldown hotend after 60 minutes + // @param turn_off_nozzle if true, the hotend temperature will be set to 0degC after 60 minutes + void saveHotendTemp(bool turn_off_nozzle); + + // Save print and park the print head + void saveAndPark(bool move_axes); + + // Resume hotend temperature, if it was cooled. Safe to call if we aren't saved. + void resumeHotendTemp(); + + // Resume position, if the extruder was parked. Safe to all if state was not saved. + void resumeUnpark(); + + // Check for any button/user input coming from the printer's UI + void checkUserInput(); + + // @brief Check whether to trigger a FINDA runout. If triggered this function will call M600 AUTO + // if SpoolJoin is enabled, otherwise M600 is called without AUTO which will prompt the user + // for the next filament slot to use + void checkFINDARunout(); + + // Entry check of all external commands. + // It can wait until the MMU becomes ready. + // Optionally, it can also emit/display an error screen and the user can decide what to do next. + // @return false if the MMU is not ready to perform the command (for whatever reason) + bool waitForMMUReady(); + + // After MMU completes a tool-change command + // the printer will push the filament by a constant distance. If the Fsensor untriggers + // at any moment the test fails. Else the test passes, and the E-motor retracts the + // filament back to its original position. + // @return false if test fails, true otherwise + bool verifyFilamentEnteredPTFE(); + + // Common processing of pushing filament into the extruder - shared by tool_change, load_to_nozzle and probably others + void toolChangeCommon(uint8_t slot); + bool toolChangeCommonOnce(uint8_t slot); + + void helpUnloadToFinda(); + void unloadInner(); + void cutFilamentInner(uint8_t slot); + + void setCurrentTool(uint8_t ex); + + ProtocolLogic logic; //!< implementation of the protocol logic layer + uint8_t extruder; //!< currently active slot in the MMU ... somewhat... not sure where to get it from yet + uint8_t tool_change_extruder; //!< only used for UI purposes + + xyz_pos_t resume_position; + int16_t resume_hotend_temp; + + ProgressCode lastProgressCode = ProgressCode::OK; + ErrorCode lastErrorCode = ErrorCode::MMU_NOT_RESPONDING; + ErrorSource lastErrorSource = ErrorSource::ErrorSourceNone; + Buttons lastButton = Buttons::NoButton; + uint16_t lastReadRegisterValue = 0; + Buttons printerButtonOperation = Buttons::NoButton; + + StepStatus logicStepLastStatus; + + enum xState _state; + + uint8_t mmu_print_saved; + bool loadFilamentStarted; + bool unloadFilamentStarted; + + uint16_t toolchange_counter; + uint16_t _tmcFailures; + }; + + } // MMU3 + +// following Marlin's way of doing stuff - one and only instance of MMU implementation in the code base +// + avoiding buggy singletons on the AVR platform +extern MMU3::MMU3 mmu3; diff --git a/Marlin/src/feature/mmu3/mmu3_crc.cpp b/Marlin/src/feature/mmu3/mmu3_crc.cpp new file mode 100644 index 0000000000..2e752c4873 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_crc.cpp @@ -0,0 +1,53 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_crc.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "mmu3_crc.h" + +#ifdef __AVR__ + #include +#endif + +namespace modules { + +namespace crc { + +uint8_t CRC8::CCITT_update(uint8_t crc, uint8_t b) { + #ifdef __AVR__ + return _crc8_ccitt_update(crc, b); + #else + return CCITT_updateCX(crc, b); + #endif +} + +} // namespace crc + +} // namespace modules + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_crc.h b/Marlin/src/feature/mmu3/mmu3_crc.h new file mode 100644 index 0000000000..f7221b38f5 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_crc.h @@ -0,0 +1,73 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_crc.h + */ + +#include + +namespace modules { + +// prevent silly indenting of the whole file + +// Contains all the necessary functions for computation of CRC +namespace crc { + +class CRC8 { +public: + // Compute/update CRC8 CCIIT from 8bits. + // Details: https://www.nongnu.org/avr-libc/user-manual/group__util__crc.html + static uint8_t CCITT_update(uint8_t crc, uint8_t b); + + static constexpr uint8_t CCITT_updateCX(uint8_t crc, uint8_t b) { + uint8_t data = crc ^ b; + for (uint8_t i = 0; i < 8; i++) { + if ((data & 0x80U) != 0) { + data <<= 1U; + data ^= 0x07U; + } + else { + data <<= 1U; + } + } + return data; + } + + // Compute/update CRC8 CCIIT from 16bits (convenience wrapper) + static constexpr uint8_t CCITT_updateW(uint8_t crc, uint16_t w) { + union U { + uint8_t b[2]; + uint16_t w; + explicit constexpr inline U(uint16_t w) + : w(w) {} + } + u(w); + return CCITT_updateCX(CCITT_updateCX(crc, u.b[0]), u.b[1]); + } +}; + +} // namespace crc + + +} // namespace modules diff --git a/Marlin/src/feature/mmu3/mmu3_error_converter.cpp b/Marlin/src/feature/mmu3/mmu3_error_converter.cpp new file mode 100644 index 0000000000..7ed53c0229 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_error_converter.cpp @@ -0,0 +1,376 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_error_converter.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "../../core/language.h" +#include "mmu3_error_converter.h" +#include "mmu_hw/error_codes.h" +#include "mmu_hw/errors_list.h" + +namespace MMU3 { + + static ButtonOperations buttonSelectedOperation = ButtonOperations::NoOperation; + + // we don't have a constexpr find_if in C++17/STL yet + template + constexpr InputIt find_if_cx(InputIt first, InputIt last, UnaryPredicate p) { + for (; first != last; ++first) { + if (p(*first)) return first; + } + return last; + } + + // Making a constexpr FindError should instruct the compiler to optimize the + // PrusaErrorCodeIndex in such a way that no searching will ever be done at + // runtime. A call to FindError then compiles to a single instruction even on + // the AVR. + // static constexpr uint8_t FindErrorIndex(uint16_t pec) { + static uint8_t FindErrorIndex(uint16_t pec) { + constexpr uint16_t errorCodesSize = sizeof(errorCodes) / sizeof(errorCodes[0]); + constexpr const auto *errorCodesEnd = errorCodes + errorCodesSize; + const auto *i = find_if_cx(errorCodes, errorCodesEnd, [pec](uint16_t ed) { + return ed == pec; + }); + return (i != errorCodesEnd) ? (i - errorCodes) : (errorCodesSize - 1); + } + + // check that the searching algorithm works + // static_assert( FindErrorIndex(ERR_MECHANICAL_FINDA_DIDNT_TRIGGER) == 0); + // static_assert( FindErrorIndex(ERR_MECHANICAL_FINDA_FILAMENT_STUCK) == 1); + // static_assert( FindErrorIndex(ERR_MECHANICAL_FSENSOR_DIDNT_TRIGGER) == 2); + // static_assert( FindErrorIndex(ERR_MECHANICAL_FSENSOR_FILAMENT_STUCK) == 3); + + constexpr ErrorCode operator&(ErrorCode a, ErrorCode b) { + return (ErrorCode)((uint16_t)a & (uint16_t)b); + } + + constexpr bool ContainsBit(ErrorCode ec, ErrorCode mask) { + return (uint16_t)ec & (uint16_t)mask; + } + + uint8_t PrusaErrorCodeIndex(const ErrorCode ec) { + switch (ec) { + case ErrorCode::FINDA_DIDNT_SWITCH_ON: + return FindErrorIndex(ERR_MECHANICAL_FINDA_DIDNT_TRIGGER); + case ErrorCode::FINDA_DIDNT_SWITCH_OFF: + return FindErrorIndex(ERR_MECHANICAL_FINDA_FILAMENT_STUCK); + case ErrorCode::FSENSOR_DIDNT_SWITCH_ON: + return FindErrorIndex(ERR_MECHANICAL_FSENSOR_DIDNT_TRIGGER); + case ErrorCode::FSENSOR_DIDNT_SWITCH_OFF: + return FindErrorIndex(ERR_MECHANICAL_FSENSOR_FILAMENT_STUCK); + case ErrorCode::FSENSOR_TOO_EARLY: + return FindErrorIndex(ERR_MECHANICAL_FSENSOR_TOO_EARLY); + case ErrorCode::FINDA_FLICKERS: + return FindErrorIndex(ERR_MECHANICAL_INSPECT_FINDA); + case ErrorCode::LOAD_TO_EXTRUDER_FAILED: + return FindErrorIndex(ERR_MECHANICAL_LOAD_TO_EXTRUDER_FAILED); + case ErrorCode::FILAMENT_EJECTED: + return FindErrorIndex(ERR_SYSTEM_FILAMENT_EJECTED); + case ErrorCode::FILAMENT_CHANGE: + return FindErrorIndex(ERR_SYSTEM_FILAMENT_CHANGE); + + case ErrorCode::STALLED_PULLEY: + case ErrorCode::MOVE_PULLEY_FAILED: + return FindErrorIndex(ERR_MECHANICAL_PULLEY_CANNOT_MOVE); + + case ErrorCode::HOMING_SELECTOR_FAILED: + return FindErrorIndex(ERR_MECHANICAL_SELECTOR_CANNOT_HOME); + case ErrorCode::MOVE_SELECTOR_FAILED: + return FindErrorIndex(ERR_MECHANICAL_SELECTOR_CANNOT_MOVE); + + case ErrorCode::HOMING_IDLER_FAILED: + return FindErrorIndex(ERR_MECHANICAL_IDLER_CANNOT_HOME); + case ErrorCode::MOVE_IDLER_FAILED: + return FindErrorIndex(ERR_MECHANICAL_IDLER_CANNOT_MOVE); + + case ErrorCode::MMU_NOT_RESPONDING: + return FindErrorIndex(ERR_CONNECT_MMU_NOT_RESPONDING); + case ErrorCode::PROTOCOL_ERROR: + return FindErrorIndex(ERR_CONNECT_COMMUNICATION_ERROR); + case ErrorCode::FILAMENT_ALREADY_LOADED: + return FindErrorIndex(ERR_SYSTEM_FILAMENT_ALREADY_LOADED); + case ErrorCode::INVALID_TOOL: + return FindErrorIndex(ERR_SYSTEM_INVALID_TOOL); + case ErrorCode::QUEUE_FULL: + return FindErrorIndex(ERR_SYSTEM_QUEUE_FULL); + case ErrorCode::VERSION_MISMATCH: + return FindErrorIndex(ERR_SYSTEM_FW_UPDATE_NEEDED); + case ErrorCode::INTERNAL: + return FindErrorIndex(ERR_SYSTEM_FW_RUNTIME_ERROR); + case ErrorCode::FINDA_VS_EEPROM_DISREPANCY: + return FindErrorIndex(ERR_SYSTEM_UNLOAD_MANUALLY); + case ErrorCode::MCU_UNDERVOLTAGE_VCC: + return FindErrorIndex(ERR_ELECTRICAL_MMU_MCU_ERROR); + default: break; + } + + // Electrical issues which can be detected somehow. + // Need to be placed before TMC-related errors in order to process couples of error bits between single ones + // and to keep the code size down. + if (ContainsBit(ec, ErrorCode::TMC_PULLEY_BIT)) { + if ((ec & ErrorCode::MMU_SOLDERING_NEEDS_ATTENTION) == ErrorCode::MMU_SOLDERING_NEEDS_ATTENTION) + return FindErrorIndex(ERR_ELECTRICAL_MMU_PULLEY_SELFTEST_FAILED); + } + else if (ContainsBit(ec, ErrorCode::TMC_SELECTOR_BIT)) { + if ((ec & ErrorCode::MMU_SOLDERING_NEEDS_ATTENTION) == ErrorCode::MMU_SOLDERING_NEEDS_ATTENTION) + return FindErrorIndex(ERR_ELECTRICAL_MMU_SELECTOR_SELFTEST_FAILED); + } + else if (ContainsBit(ec, ErrorCode::TMC_IDLER_BIT)) { + if ((ec & ErrorCode::MMU_SOLDERING_NEEDS_ATTENTION) == ErrorCode::MMU_SOLDERING_NEEDS_ATTENTION) + return FindErrorIndex(ERR_ELECTRICAL_MMU_IDLER_SELFTEST_FAILED); + } + + // TMC-related errors - multiple of these can occur at once + // - in such a case we report the first which gets found/converted into Prusa-Error-Codes (usually the fact, that one TMC has an issue is serious enough) + // By carefully ordering the checks here we can prioritize the errors being reported to the user. + if (ContainsBit(ec, ErrorCode::TMC_PULLEY_BIT)) { + if (ContainsBit(ec, ErrorCode::TMC_IOIN_MISMATCH)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_PULLEY_DRIVER_ERROR); + if (ContainsBit(ec, ErrorCode::TMC_RESET)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_PULLEY_DRIVER_RESET); + if (ContainsBit(ec, ErrorCode::TMC_UNDERVOLTAGE_ON_CHARGE_PUMP)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_PULLEY_UNDERVOLTAGE_ERROR); + if (ContainsBit(ec, ErrorCode::TMC_SHORT_TO_GROUND)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_PULLEY_DRIVER_SHORTED); + if (ContainsBit(ec, ErrorCode::TMC_OVER_TEMPERATURE_WARN)) + return FindErrorIndex(ERR_TEMPERATURE_WARNING_TMC_PULLEY_TOO_HOT); + if (ContainsBit(ec, ErrorCode::TMC_OVER_TEMPERATURE_ERROR)) + return FindErrorIndex(ERR_TEMPERATURE_TMC_PULLEY_OVERHEAT_ERROR); + } + else if (ContainsBit(ec, ErrorCode::TMC_SELECTOR_BIT)) { + if (ContainsBit(ec, ErrorCode::TMC_IOIN_MISMATCH)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_ERROR); + if (ContainsBit(ec, ErrorCode::TMC_RESET)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_RESET); + if (ContainsBit(ec, ErrorCode::TMC_UNDERVOLTAGE_ON_CHARGE_PUMP)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_SELECTOR_UNDERVOLTAGE_ERROR); + if (ContainsBit(ec, ErrorCode::TMC_SHORT_TO_GROUND)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_SHORTED); + if (ContainsBit(ec, ErrorCode::TMC_OVER_TEMPERATURE_WARN)) + return FindErrorIndex(ERR_TEMPERATURE_WARNING_TMC_SELECTOR_TOO_HOT); + if (ContainsBit(ec, ErrorCode::TMC_OVER_TEMPERATURE_ERROR)) + return FindErrorIndex(ERR_TEMPERATURE_TMC_SELECTOR_OVERHEAT_ERROR); + } + else if (ContainsBit(ec, ErrorCode::TMC_IDLER_BIT)) { + if (ContainsBit(ec, ErrorCode::TMC_IOIN_MISMATCH)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_IDLER_DRIVER_ERROR); + if (ContainsBit(ec, ErrorCode::TMC_RESET)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_IDLER_DRIVER_RESET); + if (ContainsBit(ec, ErrorCode::TMC_UNDERVOLTAGE_ON_CHARGE_PUMP)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_IDLER_UNDERVOLTAGE_ERROR); + if (ContainsBit(ec, ErrorCode::TMC_SHORT_TO_GROUND)) + return FindErrorIndex(ERR_ELECTRICAL_TMC_IDLER_DRIVER_SHORTED); + if (ContainsBit(ec, ErrorCode::TMC_OVER_TEMPERATURE_WARN)) + return FindErrorIndex(ERR_TEMPERATURE_WARNING_TMC_IDLER_TOO_HOT); + if (ContainsBit(ec, ErrorCode::TMC_OVER_TEMPERATURE_ERROR)) + return FindErrorIndex(ERR_TEMPERATURE_TMC_IDLER_OVERHEAT_ERROR); + } + + // if nothing got caught, return a generic runtime error + return FindErrorIndex(ERR_OTHER_UNKNOWN_ERROR); + } + + uint16_t PrusaErrorCode(const uint8_t i) { return pgm_read_word(errorCodes + i); } + + FSTR_P const PrusaErrorTitle(const uint8_t i) { return (FSTR_P const)pgm_read_ptr(errorTitles + i); } + FSTR_P const PrusaErrorDesc(const uint8_t i) { return (FSTR_P const)pgm_read_ptr(errorDescs + i); } + + uint8_t PrusaErrorButtons(const uint8_t i) { return pgm_read_byte(errorButtons + i); } + + FSTR_P const PrusaErrorButtonTitle(const uint8_t bi) { + // -1 represents the hidden NoOperation button which is not drawn in any way + return (FSTR_P const)pgm_read_ptr(btnOperation + bi - 1); + } + + Buttons ButtonPressed(const ErrorCode ec) { + if (buttonSelectedOperation == ButtonOperations::NoOperation || buttonSelectedOperation == ButtonOperations::MoreInfo) + return Buttons::NoButton; // no button + + const auto result = ButtonAvailable(ec); + buttonSelectedOperation = ButtonOperations::NoOperation; // Reset operation + + return result; + } + + Buttons ButtonAvailable(const ErrorCode ec) { + uint8_t ei = PrusaErrorCodeIndex(ec); + + // The list of responses which occur in mmu error dialogs + // Return button index or perform some action on the MK3 by itself (like Reset MMU) + // Based on Prusa-Error-Codes errors_list.h + // So far hardcoded, but should be generated in the future + switch (PrusaErrorCode(ei)) { + case ERR_MECHANICAL_FINDA_DIDNT_TRIGGER: + case ERR_MECHANICAL_FINDA_FILAMENT_STUCK: + case ERR_MECHANICAL_FSENSOR_DIDNT_TRIGGER: + case ERR_MECHANICAL_FSENSOR_FILAMENT_STUCK: + case ERR_MECHANICAL_FSENSOR_TOO_EARLY: + case ERR_MECHANICAL_INSPECT_FINDA: + case ERR_MECHANICAL_SELECTOR_CANNOT_MOVE: + case ERR_MECHANICAL_IDLER_CANNOT_MOVE: + case ERR_MECHANICAL_PULLEY_CANNOT_MOVE: + case ERR_SYSTEM_UNLOAD_MANUALLY: + switch (buttonSelectedOperation) { + // may be allow move selector right and left in the future + case ButtonOperations::Retry: // "Repeat action" + return Buttons::Middle; + default: + break; + } + break; + case ERR_MECHANICAL_SELECTOR_CANNOT_HOME: + case ERR_MECHANICAL_IDLER_CANNOT_HOME: + switch (buttonSelectedOperation) { + // may be allow move selector right and left in the future + case ButtonOperations::Tune: // Tune Stallguard threshold + return Buttons::TuneMMU; + case ButtonOperations::Retry: // "Repeat action" + return Buttons::Middle; + default: + break; + } + break; + case ERR_MECHANICAL_LOAD_TO_EXTRUDER_FAILED: + case ERR_SYSTEM_FILAMENT_EJECTED: + switch (buttonSelectedOperation) { + case ButtonOperations::Continue: // User solved the serious mechanical problem by hand - there is no other way around + return Buttons::Middle; + default: + break; + } + break; + case ERR_SYSTEM_FILAMENT_CHANGE: + switch (buttonSelectedOperation) { + case ButtonOperations::Load: + return Buttons::Load; + case ButtonOperations::Eject: + return Buttons::Eject; + default: + break; + } + break; + case ERR_TEMPERATURE_WARNING_TMC_PULLEY_TOO_HOT: + case ERR_TEMPERATURE_WARNING_TMC_SELECTOR_TOO_HOT: + case ERR_TEMPERATURE_WARNING_TMC_IDLER_TOO_HOT: + switch (buttonSelectedOperation) { + case ButtonOperations::Continue: // "Continue" + return Buttons::Left; + case ButtonOperations::ResetMMU: // "Reset MMU" + return Buttons::ResetMMU; + default: + break; + } + break; + + case ERR_TEMPERATURE_TMC_PULLEY_OVERHEAT_ERROR: + case ERR_TEMPERATURE_TMC_SELECTOR_OVERHEAT_ERROR: + case ERR_TEMPERATURE_TMC_IDLER_OVERHEAT_ERROR: + + case ERR_ELECTRICAL_TMC_PULLEY_DRIVER_ERROR: + case ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_ERROR: + case ERR_ELECTRICAL_TMC_IDLER_DRIVER_ERROR: + + case ERR_ELECTRICAL_TMC_PULLEY_DRIVER_RESET: + case ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_RESET: + case ERR_ELECTRICAL_TMC_IDLER_DRIVER_RESET: + + case ERR_ELECTRICAL_TMC_PULLEY_UNDERVOLTAGE_ERROR: + case ERR_ELECTRICAL_TMC_SELECTOR_UNDERVOLTAGE_ERROR: + case ERR_ELECTRICAL_TMC_IDLER_UNDERVOLTAGE_ERROR: + + case ERR_ELECTRICAL_TMC_PULLEY_DRIVER_SHORTED: + case ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_SHORTED: + case ERR_ELECTRICAL_TMC_IDLER_DRIVER_SHORTED: + + case ERR_ELECTRICAL_MMU_PULLEY_SELFTEST_FAILED: + case ERR_ELECTRICAL_MMU_SELECTOR_SELFTEST_FAILED: + case ERR_ELECTRICAL_MMU_IDLER_SELFTEST_FAILED: + + case ERR_SYSTEM_QUEUE_FULL: + case ERR_SYSTEM_FW_RUNTIME_ERROR: + case ERR_ELECTRICAL_MMU_MCU_ERROR: + switch (buttonSelectedOperation) { + case ButtonOperations::ResetMMU: // "Reset MMU" + return Buttons::ResetMMU; + default: + break; + } + break; + case ERR_CONNECT_MMU_NOT_RESPONDING: + case ERR_CONNECT_COMMUNICATION_ERROR: + case ERR_SYSTEM_FW_UPDATE_NEEDED: + switch (buttonSelectedOperation) { + case ButtonOperations::DisableMMU: // "Disable" + return Buttons::DisableMMU; + case ButtonOperations::ResetMMU: // "ResetMMU" + return Buttons::ResetMMU; + default: + break; + } + break; + case ERR_SYSTEM_FILAMENT_ALREADY_LOADED: + switch (buttonSelectedOperation) { + case ButtonOperations::Unload: // "Unload" + return Buttons::Left; + case ButtonOperations::Continue: // "Proceed/Continue" + return Buttons::Right; + default: + break; + } + break; + + case ERR_SYSTEM_INVALID_TOOL: + switch (buttonSelectedOperation) { + case ButtonOperations::StopPrint: // "Stop print" + return Buttons::StopPrint; + case ButtonOperations::ResetMMU: // "Reset MMU" + return Buttons::ResetMMU; + default: + break; + } + break; + + default: + break; + } + + return Buttons::NoButton; + } + + void SetButtonResponse(ButtonOperations rsp) { + buttonSelectedOperation = rsp; + } + + ButtonOperations GetButtonResponse() { + return buttonSelectedOperation; + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_error_converter.h b/Marlin/src/feature/mmu3/mmu3_error_converter.h new file mode 100644 index 0000000000..93a4d5e455 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_error_converter.h @@ -0,0 +1,73 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_error_converter.h + */ + +#include +#include +#include "mmu_hw/buttons.h" +#include "mmu_hw/error_codes.h" + + namespace MMU3 { + + // Translates MMU3::ErrorCode into an index of Prusa-Error-Codes + // Basically this is the way to obtain an index into all other functions in this API + uint8_t PrusaErrorCodeIndex(const ErrorCode ec); + + // @return pointer to a PROGMEM string representing the Title of the Prusa-Error-Codes error + // @param i index of the error - obtained by calling ErrorCodeIndex + FSTR_P const PrusaErrorTitle(const uint8_t i); + + // @return pointer to a PROGMEM string representing the multi-page Description of the Prusa-Error-Codes error + // @param i index of the error - obtained by calling ErrorCodeIndex + FSTR_P const PrusaErrorDesc(const uint8_t i); + + // @return the actual numerical value of the Prusa-Error-Codes error + // @param i index of the error - obtained by calling ErrorCodeIndex + uint16_t PrusaErrorCode(const uint8_t i); + + // @return Btns pair of buttons for a particular Prusa-Error-Codes error + // @param i index of the error - obtained by calling ErrorCodeIndex + uint8_t PrusaErrorButtons(const uint8_t i); + + // @return pointer to a PROGMEM string representing the Title of a button + // @param i index of the error - obtained by calling PrusaErrorButtons + extracting low or high nibble from the Btns pair + FSTR_P const PrusaErrorButtonTitle(const uint8_t bi); + + // Sets the selected button for later pick-up by the MMU state machine. + // Used to save the GUI selection/decoupling + void SetButtonResponse(const ButtonOperations rsp); + ButtonOperations GetButtonResponse(); + + // @return button index/code based on currently processed error/screen + // Clears the "pressed" button upon exit + Buttons ButtonPressed(const ErrorCode ec); + + // @return button index/code based on currently processed error/screen + // Used as a subfunction of ButtonPressed. + // Does not clear the "pressed" button upon exit + Buttons ButtonAvailable(const ErrorCode ec); + + } // MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_fsensor.cpp b/Marlin/src/feature/mmu3/mmu3_fsensor.cpp new file mode 100644 index 0000000000..32d2fac3f6 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_fsensor.cpp @@ -0,0 +1,65 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_fsensor.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "../runout.h" +#include "mmu3_fsensor.h" + +namespace MMU3 { + + #if HAS_FILAMENT_SENSOR + + FSensorBlockRunout::FSensorBlockRunout() { + runout.enabled = false; // Suppress filament runouts while loading filament. + //fsensor.setAutoLoadEnabled(false); //suppress filament autoloads while loading filament. + } + + FSensorBlockRunout::~FSensorBlockRunout() { + //fsensor.settings_init(); // restore filament runout state. + runout.reset(); + runout.enabled = true; + //SERIAL_ECHOLNPGM("FSUnBlockRunout"); + } + + #else + + FSensorBlockRunout::FSensorBlockRunout() { } + FSensorBlockRunout::~FSensorBlockRunout() { } + + #endif + + + FilamentState WhereIsFilament() { + //return fsensor.getFilamentPresent() ? FilamentState::AT_FSENSOR : FilamentState::NOT_PRESENT; + return FILAMENT_PRESENT() ? FilamentState::AT_FSENSOR : FilamentState::NOT_PRESENT; + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_fsensor.h b/Marlin/src/feature/mmu3/mmu3_fsensor.h new file mode 100644 index 0000000000..0ef4864e9f --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_fsensor.h @@ -0,0 +1,55 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_fsensor.h + */ + +#include "../../core/macros.h" +#include + +#define FILAMENT_PRESENT() (READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE) + +namespace MMU3 { + + // Can be used to block printer's filament sensor handling - to avoid erroneous injecting of M600 + // while doing a toolchange with the MMU + // In case of "no filament sensor" these methods default to an empty implementation + class FSensorBlockRunout { + public: + FSensorBlockRunout(); + ~FSensorBlockRunout(); + }; + + // Possible states of filament from the perspective of presence in various parts of the printer + // Beware, the numeric codes are important and sent into the MMU + enum class FilamentState : uint_fast8_t { + NOT_PRESENT = 0, //!< Filament sensor doesn't see the filament + AT_FSENSOR = 1, //!< Filament detected by the filament sensor, but the nozzle has not detected the filament yet + IN_NOZZLE = 2, //!< Filament detected by the filament sensor and also loaded in the nozzle + UNAVAILABLE = 3 //!< Sensor not available (likely not connected due broken cable) + }; + + FilamentState WhereIsFilament(); + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_log.cpp b/Marlin/src/feature/mmu3/mmu3_log.cpp new file mode 100644 index 0000000000..af2c92ec50 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_log.cpp @@ -0,0 +1,47 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_log.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "mmu3_log.h" + +namespace MMU3 { + + void LogEchoEvent_P(PGM_P const pstr) { + SERIAL_ECHO_START(); // @@TODO Decide MMU errors on serial line + SERIAL_MMU2(); + SERIAL_ECHOLN_P(pstr); + } + + void LogErrorEvent_P(PGM_P const pstr) { + LogEchoEvent_P(pstr); + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_log.h b/Marlin/src/feature/mmu3/mmu3_log.h new file mode 100644 index 0000000000..e4dbffeee2 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_log.h @@ -0,0 +1,82 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_log.h + */ + +#include "../../inc/MarlinConfig.h" + +namespace MMU3 { + + // Report the msg into the general logging subsystem (through Marlin's SERIAL_ECHO stuff) + // @param msg pointer to a string in PROGMEM + // On the AVR platform this variant reads the input string from PROGMEM. + // On the ARM platform it calls LogErrorEvent directly (silently expecting the compiler to optimize it away) + void LogErrorEvent_P(PGM_P const pstr); + inline void LogErrorEvent(FSTR_P const fstr) { LogErrorEvent_P(FTOP(fstr)); } + + // Report the msg into the general logging subsystem (through Marlin's SERIAL_ECHO stuff) + // @param msg pointer to a string in PROGMEM + // On the AVR platform this variant reads the input string from PROGMEM. + // On the ARM platform it calls LogErrorEvent directly (silently expecting the compiler to optimize it away) + void LogEchoEvent_P(PGM_P const pstr); + inline void LogEchoEvent(FSTR_P const fstr) { LogEchoEvent_P(FTOP(fstr)); } + +} // MMU3 + +#ifndef UNITTEST + + #define SERIAL_MMU2() { SERIAL_ECHO(F("MMU3:")); } + + #define MMU2_ECHO_MSGLN(S) do { \ + SERIAL_ECHO_START(); \ + SERIAL_MMU2(); \ + SERIAL_ECHOLN(S); \ + }while(0) + #define MMU2_ERROR_MSGLN(S) MMU2_ECHO_MSGLN(S) //! @todo Decide MMU errors on serial line + #define MMU2_ECHO_MSGRPGM(S) do { \ + SERIAL_ECHO_START(); \ + SERIAL_MMU2(); \ + SERIAL_ECHO_P(S); \ + }while(0) + #define MMU2_ERROR_MSGRPGM(S) MMU2_ECHO_MSGRPGM(S) //! @todo Decide MMU errors on serial line + #define MMU2_ECHO_MSG(S) do { \ + SERIAL_ECHO_START(); \ + SERIAL_MMU2(); \ + SERIAL_ECHO(S); \ + }while(0) + #define MMU2_ERROR_MSG(S) MMU2_ECHO_MSG(S) //! @todo Decide MMU errors on serial line + +#else // UNITTEST + + #include "stubs/stub_interfaces.h" + #define MMU2_ECHO_MSGLN(S) marlinLogSim.AppendLine(S) + #define MMU2_ERROR_MSGLN(S) marlinLogSim.AppendLine(S) + #define MMU2_ECHO_MSGRPGM(S) /* marlinLogSim.AppendLine(S) */ + #define MMU2_ERROR_MSGRPGM(S) /* marlinLogSim.AppendLine(S) */ + #define SERIAL_ECHOLNPGM(S) /* marlinLogSim.AppendLine(S) */ + #define SERIAL_ECHOPGM(S) /* */ + #define SERIAL_ECHOLN(S) /* marlinLogSim.AppendLine(S) */ + +#endif // UNITTEST diff --git a/Marlin/src/feature/mmu3/mmu3_marlin.h b/Marlin/src/feature/mmu3/mmu3_marlin.h new file mode 100644 index 0000000000..499af0f285 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_marlin.h @@ -0,0 +1,74 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_marlin.h + */ + +#include "../../inc/MarlinConfig.h" + +namespace MMU3 { + + // This interface separates Marlin1/Marlin2 from the MMU top logic layer. + // - Unify implementation among MK3 and Buddy FW + // - Enable unit testing of MMU top layer + + void extruder_move(const float distance, const float feedRate_mm_s, const bool sync=true); + void extruder_schedule_turning(const float feedRate_mm_s); + + float move_raise_z(const float delta); + + void planner_abort_queued_moves(); + void planner_synchronize(); + bool planner_any_moves(); + float stepper_get_machine_position_E_mm(); + float planner_get_current_position_E(); + void planner_set_current_position_E(float e); + xyz_pos_t planner_current_position(); + + void motion_blocking_move_xy(float rx, float ry, float feedRate_mm_s); + void motion_blocking_move_z(float z, float feedRate_mm_s); + + void nozzle_park(); + + bool marlin_printingIsActive(); + void marlin_manage_heater(); + void marlin_manage_inactivity(bool b); + void marlin_idle(bool b); + void marlin_refresh_print_state_in_ram(); + void marlin_clear_print_state_in_ram(); + void marlin_stop_and_save_print_to_ram(); + + int16_t thermal_degTargetHotend(); + int16_t thermal_degHotend(); + void thermal_setExtrudeMintemp(int16_t t); + void thermal_setTargetHotend(int16_t t); + + void safe_delay_keep_alive(uint16_t t); + + void Enable_E0(); + void Disable_E0(); + + bool xy_are_trusted(); + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp new file mode 100644 index 0000000000..f12d83772a --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp @@ -0,0 +1,173 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_marlin1.cpp + * MK3 / Marlin1 implementation of support routines for the MMU3 + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "../../MarlinCore.h" +#include "../../module/stepper.h" +#include "../../module/planner.h" +#include "../../module/temperature.h" + +#include "../pause.h" +#include "../../libs/nozzle.h" +#include "mmu3_marlin.h" + +namespace MMU3 { + + static void planner_line_to_current_position(float feedRate_mm_s) { + line_to_current_position(feedRate_mm_s); + } + + static void planner_line_to_current_position_sync(float feedRate_mm_s) { + planner_line_to_current_position(feedRate_mm_s); + planner_synchronize(); + } + + void extruder_move(const float delta, const float feedRate_mm_s, const bool sync/*=true*/) { + current_position.e += delta / planner.e_factor[active_extruder]; + planner_line_to_current_position(feedRate_mm_s); + if (sync) planner.synchronize(); + } + + float move_raise_z(const float delta) { + //return raise_z(delta); + xyze_pos_t current_position_before = current_position; + do_z_clearance_by(delta); + return (current_position - current_position_before).z; + } + + void planner_abort_queued_moves() { + //planner_abort_hard(); + quickstop_stepper(); + + // Unblock the planner. This should be safe in the + // toolchange context. Currently we are mainly aborting + // excess E-moves after detecting filament during toolchange. + // If a MMU error is reported, the planner must be unblocked + // as well so the extruder can be parked safely. + //planner_aborted = false; + // eoyilmaz: we don't need this part, the print is not aborted + } + + void planner_synchronize() { + planner.synchronize(); + } + + bool planner_any_moves() { + return planner.has_blocks_queued(); + } + + float planner_get_machine_position_E_mm() { + return current_position.e; + } + + float stepper_get_machine_position_E_mm() { + return planner.get_axis_position_mm(E_AXIS); + } + + float planner_get_current_position_E() { + return current_position.e; + } + + void planner_set_current_position_E(float e) { + current_position.e = e; + } + + xyz_pos_t planner_current_position() { + return xyz_pos_t(current_position); + } + + void motion_blocking_move_xy(float rx, float ry, float feedRate_mm_s) { + current_position.set(rx, ry); + planner_line_to_current_position_sync(feedRate_mm_s); + } + + void motion_blocking_move_z(float z, float feedRate_mm_s) { + current_position.z = z; + planner_line_to_current_position_sync(feedRate_mm_s); + } + + void nozzle_park() { + #if ANY(NOZZLE_CLEAN_FEATURE, NOZZLE_PARK_FEATURE) + #if ALL(ADVANCED_PAUSE_FEATURE) + xyz_pos_t park_point = NOZZLE_PARK_POINT; + nozzle.park(0, park_point); + #endif + #endif + } + + bool marlin_printingIsActive() { return marlin.printingIsActive(); } + + void marlin_manage_heater() { thermalManager.task(); } + + void marlin_manage_inactivity(const bool b) { marlin.idle(b); } + + void marlin_idle(const bool b) { + thermalManager.task(); + marlin.idle(b); + } + + void marlin_refresh_print_state_in_ram() { + // refresh_print_state_in_ram(); + // TODO: I don't see a comparable implementation in Marlin. + } + + void marlin_clear_print_state_in_ram() { + // clear_print_state_in_ram(); + // TODO: I don't see a comparable implementation in Marlin. + } + + void marlin_stop_and_save_print_to_ram() { + // stop_and_save_print_to_ram(0,0); + #if ENABLED(ADVANCED_PAUSE_FEATURE) + constexpr xyz_pos_t park_point = NOZZLE_PARK_POINT; + pause_print(0, park_point); + #endif + } + + int16_t thermal_degTargetHotend() { return thermalManager.degTargetHotend(0); } + int16_t thermal_degHotend() { return thermalManager.degHotend(0); } + void thermal_setExtrudeMintemp(int16_t t) { thermalManager.extrude_min_temp = t; } + void thermal_setTargetHotend(int16_t t) { thermalManager.setTargetHotend(t, 0); } + + void safe_delay_keep_alive(uint16_t t) { + marlin.idle(true); + safe_delay(t); + } + + void Enable_E0() { stepper.enable_extruder(TERN_(HAS_EXTRUDERS, 0)); } + void Disable_E0() { stepper.disable_extruder(TERN_(HAS_EXTRUDERS, 0)); } + + bool xy_are_trusted() { + return axis_is_trusted(X_AXIS) && axis_is_trusted(Y_AXIS); + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_marlin_macros.h b/Marlin/src/feature/mmu3/mmu3_marlin_macros.h new file mode 100644 index 0000000000..b277ce9805 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_marlin_macros.h @@ -0,0 +1,49 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_marlin_macros.h + */ + +// This file will not be the same on Marlin1 and Marlin2. +// Its purpose is to unify different macros in either of Marlin incarnations. + +#ifdef __AVR__ + #include "../../MarlinCore.h" + // brings _O and _T macros into MMU + #include "../../core/language.h" + #include "../../gcode/gcode.h" + // we don't have these in Marlin 2.x so just define them here again + #define _O(x) x + #define _T(x) x + #define MARLIN_KEEPALIVE_STATE_IN_PROCESS KEEPALIVE_STATE(IN_PROCESS) +#elif defined(UNITTEST) + #define _O(x) x + #define _T(x) x + #define MARLIN_KEEPALIVE_STATE_IN_PROCESS /*KEEPALIVE_STATE(IN_PROCESS) TODO*/ +#else + #include "../../gcode/gcode.h" + #define _O(x) x + #define _T(x) x + #define MARLIN_KEEPALIVE_STATE_IN_PROCESS KEEPALIVE_STATE(IN_PROCESS) +#endif diff --git a/Marlin/src/feature/mmu3/mmu3_power.cpp b/Marlin/src/feature/mmu3/mmu3_power.cpp new file mode 100644 index 0000000000..1782cb49fc --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_power.cpp @@ -0,0 +1,65 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_power.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "mmu3.h" +#include "mmu3_power.h" + +#include "../../MarlinCore.h" + +#include "../../core/macros.h" +#include "../../core/boards.h" +#include "../../pins/pins.h" + +namespace MMU3 { + + // On MK3 we cannot do actual power cycle on HW. Instead trigger a hardware reset. + void power_on() { + #if PIN_EXISTS(MMU_RST) + OUT_WRITE(MMU_RST_PIN, HIGH); + #endif + power_reset(); + } + + void power_off() {} + + void power_reset() { + #if PIN_EXISTS(MMU_RST) // HW - pulse reset pin + WRITE(MMU_RST_PIN, LOW); + safe_delay(100); + WRITE(MMU_RST_PIN, HIGH); + #else + mmu3.reset(MMU3::Software); // TODO: Needs redesign. This power implementation shouldn't know anything about the MMU itself + #endif + // otherwise HW reset is not available + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_power.h b/Marlin/src/feature/mmu3/mmu3_power.h new file mode 100644 index 0000000000..77259073a1 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_power.h @@ -0,0 +1,32 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_power.h + */ + +namespace MMU3 { + void power_on(); + void power_off(); + void power_reset(); +} diff --git a/Marlin/src/feature/mmu3/mmu3_progress_converter.cpp b/Marlin/src/feature/mmu3/mmu3_progress_converter.cpp new file mode 100644 index 0000000000..8933f2d5fd --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_progress_converter.cpp @@ -0,0 +1,79 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_progress_converter.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "../../core/language.h" +#include "mmu3_progress_converter.h" +#include "mmu_hw/progress_codes.h" +#include "mmu_hw/errors_list.h" + +namespace MMU3 { + + FSTR_P const progressTexts[] PROGMEM = { + GET_TEXT_F(MSG_PROGRESS_OK), // TODO: Generic messages for Marlin + GET_TEXT_F(MSG_PROGRESS_ENGAGE_IDLER), // reused below + GET_TEXT_F(MSG_PROGRESS_DISENGAGE_IDLER), // reused below + GET_TEXT_F(MSG_PROGRESS_UNLOAD_FINDA), + GET_TEXT_F(MSG_PROGRESS_UNLOAD_PULLEY), + GET_TEXT_F(MSG_PROGRESS_FEED_FINDA), + GET_TEXT_F(MSG_PROGRESS_FEED_EXTRUDER), + GET_TEXT_F(MSG_PROGRESS_FEED_NOZZLE), + GET_TEXT_F(MSG_PROGRESS_AVOID_GRIND), + GET_TEXT_F(MSG_FINISHING_MOVEMENTS), + GET_TEXT_F(MSG_PROGRESS_DISENGAGE_IDLER), // err disengaging idler is the same text + GET_TEXT_F(MSG_PROGRESS_ENGAGE_IDLER), // engage dtto. + GET_TEXT_F(MSG_PROGRESS_WAIT_USER), + GET_TEXT_F(MSG_PROGRESS_ERR_INTERNAL), + GET_TEXT_F(MSG_PROGRESS_ERR_HELP_FIL), + GET_TEXT_F(MSG_PROGRESS_ERR_TMC), + GET_TEXT_F(MSG_UNLOADING_FILAMENT), + GET_TEXT_F(MSG_LOADING_FILAMENT), + GET_TEXT_F(MSG_PROGRESS_SELECT_SLOT), + GET_TEXT_F(MSG_PROGRESS_PREPARE_BLADE), + GET_TEXT_F(MSG_PROGRESS_PUSH_FILAMENT), + GET_TEXT_F(MSG_PROGRESS_PERFORM_CUT), + GET_TEXT_F(MSG_PROGRESSPSTRETURN_SELECTOR), + GET_TEXT_F(MSG_PROGRESS_PARK_SELECTOR), + GET_TEXT_F(MSG_PROGRESS_EJECT_FILAMENT), + GET_TEXT_F(MSG_PROGRESSPSTRETRACT_FINDA), + GET_TEXT_F(MSG_PROGRESS_HOMING), + GET_TEXT_F(MSG_PROGRESS_MOVING_SELECTOR), + GET_TEXT_F(MSG_PROGRESS_FEED_FSENSOR) + }; + + FSTR_P const ProgressCodeToText(const ProgressCode pc) { + // @@TODO ?? a better fallback option? + return (int(pc) < COUNT(progressTexts)) + ? static_cast(pgm_read_ptr(&progressTexts[(uint16_t)pc])) + : static_cast(pgm_read_ptr(&progressTexts[0])); + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_progress_converter.h b/Marlin/src/feature/mmu3/mmu3_progress_converter.h new file mode 100644 index 0000000000..e7b1d86821 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_progress_converter.h @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_progress_converter.h + */ + +#include "mmu_hw/progress_codes.h" + +#include "../../HAL/shared/Marduino.h" + +namespace MMU3 { + +FSTR_P const ProgressCodeToText(const ProgressCode pc); + +} diff --git a/Marlin/src/feature/mmu3/mmu3_protocol.cpp b/Marlin/src/feature/mmu3/mmu3_protocol.cpp new file mode 100644 index 0000000000..739599f142 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_protocol.cpp @@ -0,0 +1,418 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_protocol.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "mmu3_protocol.h" + +// protocol definition +// command: Q0 +// meaning: query operation status +// Query/command: query +// Expected reply from the MMU: +// any of the running operation statuses: OID: [T|L|U|E|C|W|K][0-4] +// P[0-9] : command being processed i.e. operation running, may contain a state number +// E[0-9][0-9] : error 1-9 while doing a tool change +// F[0-9] : operation finished - will be repeated to "Q" messages until a new command is issued + +namespace modules { +namespace protocol { + + // decoding automaton + // states: input -> transition into state + // Code QTLMUXPSBEWK -> msgcode + // \n ->start + // * ->error + // error \n ->start + // * ->error + // msgcode 0-9 ->msgvalue + // * ->error + // msgvalue 0-9 ->msgvalue + // \n ->start successfully accepted command + + DecodeStatus Protocol::DecodeRequest(uint8_t c) { + switch (rqState) { + case RequestStates::Code: + switch (c) { + case 'Q': + case 'T': + case 'L': + case 'M': + case 'U': + case 'X': + case 'P': + case 'S': + case 'B': + case 'E': + case 'W': // write is gonna be a special one + case 'K': + case 'F': + case 'f': + case 'H': + case 'R': + requestMsg.code = (RequestMsgCodes)c; + requestMsg.value = 0; + requestMsg.value2 = 0; + requestMsg.crc8 = 0; + rqState = (c == 'W') ? RequestStates::Address : RequestStates::Value; // prepare special automaton path for Write commands + return DecodeStatus::NeedMoreData; + default: + requestMsg.code = RequestMsgCodes::unknown; + rqState = RequestStates::Error; + return DecodeStatus::Error; + } + case RequestStates::Value: + if (IsHexDigit(c)) { + requestMsg.value <<= 4U; + requestMsg.value |= Char2Nibble(c); + return DecodeStatus::NeedMoreData; + } + else if (IsCRCSeparator(c)) { + rqState = RequestStates::CRC; + return DecodeStatus::NeedMoreData; + } + else { + requestMsg.code = RequestMsgCodes::unknown; + rqState = RequestStates::Error; + return DecodeStatus::Error; + } + case RequestStates::Address: + if (IsHexDigit(c)) { + requestMsg.value <<= 4U; + requestMsg.value |= Char2Nibble(c); + return DecodeStatus::NeedMoreData; + } + else if (c == ' ') { // end of address, value coming + rqState = RequestStates::WriteValue; + return DecodeStatus::NeedMoreData; + } + else { + requestMsg.code = RequestMsgCodes::unknown; + rqState = RequestStates::Error; + return DecodeStatus::Error; + } + case RequestStates::WriteValue: + if (IsHexDigit(c)) { + requestMsg.value2 <<= 4U; + requestMsg.value2 |= Char2Nibble(c); + return DecodeStatus::NeedMoreData; + } + else if (IsCRCSeparator(c)) { + rqState = RequestStates::CRC; + return DecodeStatus::NeedMoreData; + } + else { + requestMsg.code = RequestMsgCodes::unknown; + rqState = RequestStates::Error; + return DecodeStatus::Error; + } + case RequestStates::CRC: + if (IsHexDigit(c)) { + requestMsg.crc8 <<= 4U; + requestMsg.crc8 |= Char2Nibble(c); + return DecodeStatus::NeedMoreData; + } + else if (IsNewLine(c)) { + // check CRC at this spot + if (requestMsg.crc8 != requestMsg.ComputeCRC8()) { + // CRC mismatch + requestMsg.code = RequestMsgCodes::unknown; + rqState = RequestStates::Error; + return DecodeStatus::Error; + } + else { + rqState = RequestStates::Code; + return DecodeStatus::MessageCompleted; + } + } + else { + requestMsg.code = RequestMsgCodes::unknown; + rqState = RequestStates::Error; + return DecodeStatus::Error; + } + default: // case error: + if (IsNewLine(c)) { + rqState = RequestStates::Code; + return DecodeStatus::MessageCompleted; + } + else { + requestMsg.code = RequestMsgCodes::unknown; + rqState = RequestStates::Error; + return DecodeStatus::Error; + } + } + } + + uint8_t Protocol::EncodeRequest(const RequestMsg &msg, uint8_t *txbuff) { + txbuff[0] = (uint8_t)msg.code; + uint8_t i = 1 + UInt8ToHex(msg.value, txbuff + 1); + + i += AppendCRC(msg.getCRC(), txbuff + i); + + txbuff[i] = '\n'; + ++i; + return i; + static_assert(7 <= MaxRequestSize(), "Request message length exceeded the maximum size, increase the magic constant in MaxRequestSize()"); + } + + uint8_t Protocol::EncodeWriteRequest(uint8_t address, uint16_t value, uint8_t *txbuff) { + const RequestMsg msg(RequestMsgCodes::Write, address, value); + uint8_t i = BeginEncodeRequest(msg, txbuff); + // dump the value + i += UInt16ToHex(value, txbuff + i); + + i += AppendCRC(msg.getCRC(), txbuff + i); + + txbuff[i] = '\n'; + ++i; + return i; + } + + DecodeStatus Protocol::DecodeResponse(uint8_t c) { + switch (rspState) { + case ResponseStates::RequestCode: + switch (c) { + case 'Q': + case 'T': + case 'L': + case 'M': + case 'U': + case 'X': + case 'P': + case 'S': + case 'B': + case 'E': + case 'W': + case 'K': + case 'F': + case 'f': + case 'H': + case 'R': + responseMsg.request.code = (RequestMsgCodes)c; + responseMsg.request.value = 0; + responseMsg.request.value2 = 0; + responseMsg.request.crc8 = 0; + rspState = ResponseStates::RequestValue; + return DecodeStatus::NeedMoreData; + case 0x0a: + case 0x0d: + // skip leading whitespace if any (makes integration with other SW easier/tolerant) + return DecodeStatus::NeedMoreData; + default: + rspState = ResponseStates::Error; + return DecodeStatus::Error; + } + case ResponseStates::RequestValue: + if (IsHexDigit(c)) { + responseMsg.request.value <<= 4U; + responseMsg.request.value += Char2Nibble(c); + return DecodeStatus::NeedMoreData; + } + else if (c == ' ') { + rspState = ResponseStates::ParamCode; + return DecodeStatus::NeedMoreData; + } + else { + rspState = ResponseStates::Error; + return DecodeStatus::Error; + } + case ResponseStates::ParamCode: + switch (c) { + case 'P': + case 'E': + case 'F': + case 'A': + case 'R': + case 'B': + rspState = ResponseStates::ParamValue; + responseMsg.paramCode = (ResponseMsgParamCodes)c; + responseMsg.paramValue = 0; + return DecodeStatus::NeedMoreData; + default: + responseMsg.paramCode = ResponseMsgParamCodes::unknown; + rspState = ResponseStates::Error; + return DecodeStatus::Error; + } + case ResponseStates::ParamValue: + if (IsHexDigit(c)) { + responseMsg.paramValue <<= 4U; + responseMsg.paramValue += Char2Nibble(c); + return DecodeStatus::NeedMoreData; + } + else if (IsCRCSeparator(c)) { + rspState = ResponseStates::CRC; + return DecodeStatus::NeedMoreData; + } + else { + responseMsg.paramCode = ResponseMsgParamCodes::unknown; + rspState = ResponseStates::Error; + return DecodeStatus::Error; + } + case ResponseStates::CRC: + if (IsHexDigit(c)) { + responseMsg.request.crc8 <<= 4U; + responseMsg.request.crc8 += Char2Nibble(c); + return DecodeStatus::NeedMoreData; + } + else if (IsNewLine(c)) { + // check CRC at this spot + if (responseMsg.request.crc8 != responseMsg.ComputeCRC8()) { + // CRC mismatch + responseMsg.paramCode = ResponseMsgParamCodes::unknown; + rspState = ResponseStates::Error; + return DecodeStatus::Error; + } + else { + rspState = ResponseStates::RequestCode; + return DecodeStatus::MessageCompleted; + } + } + else { + responseMsg.paramCode = ResponseMsgParamCodes::unknown; + rspState = ResponseStates::Error; + return DecodeStatus::Error; + } + default: // case error: + if (IsNewLine(c)) { + rspState = ResponseStates::RequestCode; + return DecodeStatus::MessageCompleted; + } + else { + responseMsg.paramCode = ResponseMsgParamCodes::unknown; + return DecodeStatus::Error; + } + } + } + + uint8_t Protocol::EncodeResponseCmdAR(const RequestMsg &msg, ResponseMsgParamCodes ar, uint8_t *txbuff) { + // BEWARE: + // ResponseMsg rsp(RequestMsg(msg.code, msg.value), ar, 0); + // ... is NOT the same as: + // ResponseMsg rsp(msg, ar, 0); + // ... because of the usually unused parameter value2 (which only comes non-zero in write requests). + // It took me a few hours to find out why the CRC from the MMU never matched all the other sides (unit tests and the MK3S) + // It is because this was the only place where the original request kept its value2 non-zero. + // In the response, we must make sure value2 is actually zero unless being sent along with it (which is not right now) + const ResponseMsg rsp(RequestMsg(msg.code, msg.value), ar, 0); // this needs some cleanup @@TODO - check assembly how bad is it + uint8_t i = BeginEncodeRequest(rsp.request, txbuff); + txbuff[i] = (uint8_t)ar; + ++i; + i += AppendCRC(rsp.getCRC(), txbuff + i); + txbuff[i] = '\n'; + ++i; + return i; + } + + uint8_t Protocol::EncodeResponseReadFINDA(const RequestMsg &msg, uint8_t findaValue, uint8_t *txbuff) { + return EncodeResponseRead(msg, true, findaValue, txbuff); + } + + uint8_t Protocol::EncodeResponseQueryOperation(const RequestMsg &msg, ResponseCommandStatus rcs, uint8_t *txbuff) { + const ResponseMsg rsp(msg, rcs.code, rcs.value); + uint8_t i = BeginEncodeRequest(msg, txbuff); + txbuff[i] = (uint8_t)rsp.paramCode; + ++i; + i += UInt16ToHex(rsp.paramValue, txbuff + i); + i += AppendCRC(rsp.getCRC(), txbuff + i); + txbuff[i] = '\n'; + return i + 1; + } + + uint8_t Protocol::EncodeResponseRead(const RequestMsg &msg, bool accepted, uint16_t value2, uint8_t *txbuff) { + const ResponseMsg rsp(msg, + accepted ? ResponseMsgParamCodes::Accepted : ResponseMsgParamCodes::Rejected, + accepted ? value2 : 0 // be careful about this value for CRC computation - rejected status doesn't have any meaningful value which could be reconstructed from the textual form of the message + ); + uint8_t i = BeginEncodeRequest(msg, txbuff); + txbuff[i] = (uint8_t)rsp.paramCode; + ++i; + if (accepted) + // dump the value + i += UInt16ToHex(value2, txbuff + i); + i += AppendCRC(rsp.getCRC(), txbuff + i); + txbuff[i] = '\n'; + return i + 1; + } + + uint8_t Protocol::UInt8ToHex(uint8_t value, uint8_t *dst) { + if (value == 0) { + *dst = '0'; + return 1; + } + + uint8_t v = value >> 4U; + uint8_t charsOut = 1; + if (v != 0) { // skip the first '0' if any + *dst = Nibble2Char(v); + ++dst; + charsOut = 2; + } + v = value & 0xfU; + *dst = Nibble2Char(v); + return charsOut; + } + + uint8_t Protocol::UInt16ToHex(uint16_t value, uint8_t *dst) { + constexpr uint16_t topNibbleMask = 0xf000; + if (value == 0) { + *dst = '0'; + return 1; + } + // skip initial zeros + uint8_t charsOut = 4; + while ((value & topNibbleMask) == 0) { + value <<= 4U; + --charsOut; + } + for (uint8_t i = 0; i < charsOut; ++i) { + uint8_t n = (value & topNibbleMask) >> (8U + 4U); + value <<= 4U; + *dst = Nibble2Char(n); + ++dst; + } + return charsOut; + } + + uint8_t Protocol::BeginEncodeRequest(const RequestMsg &msg, uint8_t *dst) { + dst[0] = (uint8_t)msg.code; + + uint8_t i = 1 + UInt8ToHex(msg.value, dst + 1); + + dst[i] = ' '; + return i + 1; + } + + uint8_t Protocol::AppendCRC(uint8_t crc, uint8_t *dst) { + dst[0] = '*'; // reprap-style separator of CRC + return 1 + UInt8ToHex(crc, dst + 1); + } + +} // namespace protocol +} // namespace modules + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_protocol.h b/Marlin/src/feature/mmu3/mmu3_protocol.h new file mode 100644 index 0000000000..f9553b58c8 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_protocol.h @@ -0,0 +1,318 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_protocol.h + */ + +#include "../../MarlinCore.h" + +#include +#include "mmu3_crc.h" + +// prevent ARM HAL macros from breaking our code +#undef CRC + +namespace modules { + +// @brief The MMU communication protocol implementation and related stuff. +// +// See description of the new protocol in the MMU 2021 doc +namespace protocol { + + // Definition of request message codes + enum class RequestMsgCodes : uint8_t { + unknown = 0, + Query = 'Q', + Tool = 'T', + Load = 'L', + Mode = 'M', + Unload = 'U', + Reset = 'X', + Finda = 'P', + Version = 'S', + Button = 'B', + Eject = 'E', + Write = 'W', + Cut = 'K', + FilamentType = 'F', + FilamentSensor = 'f', + Home = 'H', + Read = 'R' + }; + + // Definition of response message parameter codes + enum class ResponseMsgParamCodes : uint8_t { + unknown = 0, + Processing = 'P', + Error = 'E', + Finished = 'F', + Accepted = 'A', + Rejected = 'R', + Button = 'B'// the MMU registered a button press and is sending it to the printer for processing + }; + + // A request message - requests are being sent by the printer into the MMU. + struct RequestMsg { + RequestMsgCodes code; //!< code of the request message + uint8_t value; //!< value of the request message or address of variable to read/write + uint16_t value2; //!< in case or write messages - value to be written into the register + + // CRC8 check - please note we abuse this byte for CRC of ResponseMsgs as well. + // The crc8 byte itself is not added into the CRC computation (obviously ;) ) + // Beware - adding any members of this data structure may need changing the way CRC is being computed! + uint8_t crc8; + + constexpr uint8_t ComputeCRC8() const { + uint8_t crc = 0; + crc = modules::crc::CRC8::CCITT_updateCX(0, (uint8_t)code); + crc = modules::crc::CRC8::CCITT_updateCX(crc, value); + crc = modules::crc::CRC8::CCITT_updateW(crc, value2); + return crc; + } + + // @param code of the request message + // @param value of the request message + inline constexpr RequestMsg(RequestMsgCodes code, uint8_t value) + : code(code) + , value(value) + , value2(0) + , crc8(ComputeCRC8()) { + } + + // Intended for write requests + // @param code of the request message ('W') + // @param address of the register + // @param value to write into the register + inline constexpr RequestMsg(RequestMsgCodes code, uint8_t address, uint16_t value) + : code(code) + , value(address) + , value2(value) + , crc8(ComputeCRC8()) {} + + constexpr uint8_t getCRC() const { return crc8; } + }; + + // A response message - responses are being sent from the MMU into the printer as a response to a request message. + struct ResponseMsg { + RequestMsg request; //!< response is always preceded by the request message + ResponseMsgParamCodes paramCode; //!< code of the parameter + uint16_t paramValue; //!< value of the parameter + + constexpr uint8_t ComputeCRC8() const { + uint8_t crc = request.ComputeCRC8(); + crc = modules::crc::CRC8::CCITT_updateCX(crc, (uint8_t)paramCode); + crc = modules::crc::CRC8::CCITT_updateW(crc, paramValue); + return crc; + } + + // @param request the source request message this response is a reply to + // @param paramCode code of the parameter + // @param paramValue value of the parameter + inline constexpr ResponseMsg(RequestMsg request, ResponseMsgParamCodes paramCode, uint16_t paramValue) + : request(request) + , paramCode(paramCode) + , paramValue(paramValue) { + this->request.crc8 = ComputeCRC8(); + } + + constexpr uint8_t getCRC() const { return request.crc8; } + }; + + // Combined commandStatus and its value into one data structure (optimization purposes) + struct ResponseCommandStatus { + ResponseMsgParamCodes code; + uint16_t value; + inline constexpr ResponseCommandStatus(ResponseMsgParamCodes code, uint16_t value) + : code(code) + , value(value) {} + }; + + // Message decoding return values + enum class DecodeStatus : uint_fast8_t { + MessageCompleted, //!< message completed and successfully lexed + NeedMoreData, //!< message incomplete yet, waiting for another byte to come + Error, //!< input character broke message decoding + }; + + // Protocol class is responsible for creating/decoding messages in Rx/Tx buffer + // + // Beware - in the decoding more, it is meant to be a stateful instance which works through public methods + // processing one input byte per call. + class Protocol { + public: + Protocol() + : rqState(RequestStates::Code) + , requestMsg(RequestMsgCodes::unknown, 0) + , rspState(ResponseStates::RequestCode) + , responseMsg(RequestMsg(RequestMsgCodes::unknown, 0), ResponseMsgParamCodes::unknown, 0) {} + + // Takes the input byte c and steps one step through the state machine + // @return state of the message being decoded + DecodeStatus DecodeRequest(uint8_t c); + + // Decodes response message in rxbuff + // @return decoded response message structure + DecodeStatus DecodeResponse(uint8_t c); + + // Encodes request message msg into txbuff memory + // It is expected the txbuff is large enough to fit the message + // @return number of bytes written into txbuff + static uint8_t EncodeRequest(const RequestMsg &msg, uint8_t *txbuff); + + // Encodes Write request message msg into txbuff memory + // It is expected the txbuff is large enough to fit the message + // @return number of bytes written into txbuff + static uint8_t EncodeWriteRequest(uint8_t address, uint16_t value, uint8_t *txbuff); + + // @return the maximum byte length necessary to encode a request message + // Beneficial in case of pre-allocating a buffer for encoding a RequestMsg. + static constexpr uint8_t MaxRequestSize() { return 13; } + + // @return the maximum byte length necessary to encode a response message + // Beneficial in case of pre-allocating a buffer for encoding a ResponseMsg. + static constexpr uint8_t MaxResponseSize() { return 14; } + + // Encode generic response Command Accepted or Rejected + // @param msg source request message for this response + // @param ar code of response parameter + // @param txbuff where to format the message + // @return number of bytes written into txbuff + static uint8_t EncodeResponseCmdAR(const RequestMsg &msg, ResponseMsgParamCodes ar, uint8_t *txbuff); + + // Encode response to Read FINDA query + // @param msg source request message for this response + // @param findaValue 1/0 (on/off) status of FINDA + // @param txbuff where to format the message + // @return number of bytes written into txbuff + static uint8_t EncodeResponseReadFINDA(const RequestMsg &msg, uint8_t findaValue, uint8_t *txbuff); + + // Encode response to Version query + // @param msg source request message for this response + // @param value version number (0-255) + // @param txbuff where to format the message + // @return number of bytes written into txbuff + static uint8_t EncodeResponseVersion(const RequestMsg &msg, uint16_t value, uint8_t *txbuff); + + // Encode response to Query operation status + // @param msg source request message for this response + // @param code status of operation (Processing, Error, Finished) + // @param value related to status of operation(e.g. error code or progress) + // @param txbuff where to format the message + // @return number of bytes written into txbuff + static uint8_t EncodeResponseQueryOperation(const RequestMsg &msg, ResponseCommandStatus rcs, uint8_t *txbuff); + + // Encode response to Read query + // @param msg source request message for this response + // @param accepted true if the read query was accepted + // @param value2 variable value + // @param txbuff where to format the message + // @return number of bytes written into txbuff + static uint8_t EncodeResponseRead(const RequestMsg &msg, bool accepted, uint16_t value2, uint8_t *txbuff); + + // @return the most recently lexed request message + inline const RequestMsg GetRequestMsg() const { return requestMsg; } + + // @return the most recently lexed response message + inline const ResponseMsg GetResponseMsg() const { return responseMsg; } + + // resets the internal request decoding state (typically after an error) + void ResetRequestDecoder() { + rqState = RequestStates::Code; + } + + // resets the internal response decoding state (typically after an error) + void ResetResponseDecoder() { + rspState = ResponseStates::RequestCode; + } + + #ifndef UNITTEST + private: + #endif + + enum class RequestStates : uint8_t { + Code, //!< starting state - expects message code + Value, //!< expecting code value + Address, //!< expecting address for Write command + WriteValue, //!< value to be written (Write command) + CRC, //!< CRC + Error //!< automaton in error state + }; + + RequestStates rqState; + RequestMsg requestMsg; + + enum class ResponseStates : uint8_t { + RequestCode, //!< starting state - expects message code + RequestValue, //!< expecting code value + ParamCode, //!< expecting param code + ParamValue, //!< expecting param value + CRC, //!< expecting CRC value + Error //!< automaton in error state + }; + + ResponseStates rspState; + ResponseMsg responseMsg; + + static constexpr bool IsNewLine(uint8_t c) { + return c == '\n' || c == '\r'; + } + static constexpr bool IsDigit(uint8_t c) { + return c >= '0' && c <= '9'; + } + static constexpr bool IsCRCSeparator(uint8_t c) { + return c == '*'; + } + static constexpr bool IsHexDigit(uint8_t c) { + return (c >= '0' && c <= '9') || (c >= 'a' && c <= 'f'); + } + static constexpr uint8_t Char2Nibble(uint8_t c) { + switch (c) { + case '0' ... '9': return c - '0'; + case 'a' ... 'f': return c - 'a' + 10; + default: return 0; + } + } + + static constexpr uint8_t Nibble2Char(uint8_t n) { + switch (n) { + case 0x0 ... 0x9: return n + '0'; + case 0xA ... 0xF: return n - 10 + 'a'; + default: return 0; + } + } + + // @return number of characters written + static uint8_t UInt8ToHex(uint8_t value, uint8_t *dst); + + // @return number of characters written + static uint8_t UInt16ToHex(uint16_t value, uint8_t *dst); + + static uint8_t BeginEncodeRequest(const RequestMsg &msg, uint8_t *dst); + + static uint8_t AppendCRC(uint8_t crc, uint8_t *dst); + }; + +} // namespace protocol +} // namespace modules + diff --git a/Marlin/src/feature/mmu3/mmu3_protocol_logic.cpp b/Marlin/src/feature/mmu3/mmu3_protocol_logic.cpp new file mode 100644 index 0000000000..4323925b6b --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_protocol_logic.cpp @@ -0,0 +1,899 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_protocol_logic.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "mmu3_protocol_logic.h" +#include "mmu3_log.h" +#include "mmu3_fsensor.h" + + #ifdef __AVR__ + // on MK3/S/+ we shuffle the timers a bit, thus "_millis" may not equal "millis" + // #include "system_timer.h" + #define _millis millis + #else + // irrelevant on Buddy FW, just keep "_millis" as "millis" + // #include + #define _millis millis + #ifdef UNITTEST + #define strncmp_P strncmp + #else + #include "../../core/serial.h" + #endif + #endif + + #include + #include "mmu3_supported_version.h" + +namespace MMU3 { + + static constexpr uint8_t supportedMmuFWVersion[] PROGMEM = { mmuVersionMajor, mmuVersionMinor, mmuVersionPatch }; + + const Register ProtocolLogic::regs8Addrs[ProtocolLogic::regs8Count] PROGMEM = { + Register::FINDA_State, // FINDA state + Register::Set_Get_Selector_Slot, // Selector slot + Register::Set_Get_Idler_Slot, // Idler slot + }; + + const Register ProtocolLogic::regs16Addrs[ProtocolLogic::regs16Count] PROGMEM = { + Register::MMU_Errors, // MMU errors - aka statistics + Register::Get_Pulley_Position, // Pulley position [mm] + }; + + const Register ProtocolLogic::initRegs8Addrs[ProtocolLogic::initRegs8Count] PROGMEM = { + Register::Extra_Load_Distance, // Extra load distance [mm] + Register::Pulley_Slow_Feedrate, // Pulley slow feedrate [mm/s] + }; + + void ProtocolLogic::CheckAndReportAsyncEvents() { + // even when waiting for a query period, we need to report a change in filament sensor's state + // - it is vital for a precise synchronization of moves of the printer and the MMU + uint8_t fs = (uint8_t)WhereIsFilament(); + if (fs != lastFSensor) + SendAndUpdateFilamentSensor(); + } + + void ProtocolLogic::SendQuery() { + SendMsg(RequestMsg(RequestMsgCodes::Query, 0)); + scopeState = ScopeState::QuerySent; + } + + void ProtocolLogic::StartReading8bitRegisters() { + regIndex = 0; + SendReadRegister(pgm_read_byte(regs8Addrs + regIndex), ScopeState::Reading8bitRegisters); + } + + void ProtocolLogic::ProcessRead8bitRegister() { + regs8[regIndex] = rsp.paramValue; + ++regIndex; + if (regIndex >= regs8Count) + // proceed with reading 16bit registers + StartReading16bitRegisters(); + else + SendReadRegister(pgm_read_byte(regs8Addrs + regIndex), ScopeState::Reading8bitRegisters); + } + + void ProtocolLogic::StartReading16bitRegisters() { + regIndex = 0; + SendReadRegister(pgm_read_byte(regs16Addrs + regIndex), ScopeState::Reading16bitRegisters); + } + + ProtocolLogic::ScopeState __attribute__((noinline)) ProtocolLogic::ProcessRead16bitRegister(ProtocolLogic::ScopeState stateAtEnd) { + regs16[regIndex] = rsp.paramValue; + ++regIndex; + if (regIndex >= regs16Count) + return stateAtEnd; + else + SendReadRegister(pgm_read_byte(regs16Addrs + regIndex), ScopeState::Reading16bitRegisters); + return ScopeState::Reading16bitRegisters; + } + + void ProtocolLogic::StartWritingInitRegisters() { + regIndex = 0; + SendWriteRegister(pgm_read_byte(initRegs8Addrs + regIndex), initRegs8[regIndex], ScopeState::WritingInitRegisters); + } + + bool __attribute__((noinline)) ProtocolLogic::ProcessWritingInitRegister() { + ++regIndex; + if (regIndex >= initRegs8Count) + return true; + else + SendWriteRegister(pgm_read_byte(initRegs8Addrs + regIndex), initRegs8[regIndex], ScopeState::WritingInitRegisters); + return false; + } + + void ProtocolLogic::SendAndUpdateFilamentSensor() { + SendMsg(RequestMsg(RequestMsgCodes::FilamentSensor, lastFSensor = (uint8_t)WhereIsFilament())); + scopeState = ScopeState::FilamentSensorStateSent; + } + + void ProtocolLogic::SendButton(uint8_t btn) { + SendMsg(RequestMsg(RequestMsgCodes::Button, btn)); + scopeState = ScopeState::ButtonSent; + } + + void ProtocolLogic::SendVersion(uint8_t stage) { + SendMsg(RequestMsg(RequestMsgCodes::Version, stage)); + scopeState = (ScopeState)((uint_fast8_t)ScopeState::S0Sent + stage); + } + + void ProtocolLogic::SendReadRegister(uint8_t index, ScopeState nextState) { + SendMsg(RequestMsg(RequestMsgCodes::Read, index)); + scopeState = nextState; + } + + void ProtocolLogic::SendWriteRegister(uint8_t index, uint16_t value, ScopeState nextState) { + SendWriteMsg(RequestMsg(RequestMsgCodes::Write, index, value)); + scopeState = nextState; + } + + // searches for "ok\n" in the incoming serial data (that's the usual response of the old MMU FW) + struct OldMMUFWDetector { + uint8_t ok; + inline constexpr OldMMUFWDetector() + : ok(0) {} + + enum class State : uint8_t { + MatchingPart, + SomethingElse, + Matched + }; + + // @return true when "ok\n" gets detected + State Detect(uint8_t c) { + // consume old MMU FW's data if any -> avoid confusion of protocol decoder + if (ok == 0 && c == 'o') { + ++ok; + return State::MatchingPart; + } + else if (ok == 1 && c == 'k') { + ++ok; + return State::Matched; + } + return State::SomethingElse; + } + }; + + StepStatus ProtocolLogic::ExpectingMessage() { + int bytesConsumed = 0; + int c = -1; + + OldMMUFWDetector oldMMUh4x0r; // old MMU FW hacker ;) + + // try to consume as many rx bytes as possible (until a message has been completed) + while ((c = MMU_SERIAL.read()) >= 0) { + ++bytesConsumed; + RecordReceivedByte(c); + switch (protocol.DecodeResponse(c)) { + case DecodeStatus::MessageCompleted: + rsp = protocol.GetResponseMsg(); + LogResponse(); + // @@TODO reset direction of communication + RecordUARTActivity(); // something has happened on the UART, update the timeout record + return MessageReady; + case DecodeStatus::NeedMoreData: + break; + case DecodeStatus::Error: { + // consume old MMU FW's data if any -> avoid confusion of protocol decoder + auto old = oldMMUh4x0r.Detect(c); + if (old == OldMMUFWDetector::State::Matched) + // Old MMU FW 1.0.6 detected. Firmwares are incompatible. + return VersionMismatch; + else if (old == OldMMUFWDetector::State::MatchingPart) + break; + } + // [[fallthrough]]; // otherwise + // fall through + default: + RecordUARTActivity(); // something has happened on the UART, update the timeout record + return ProtocolError; + } + } + if (bytesConsumed != 0) { + RecordUARTActivity(); // something has happened on the UART, update the timeout record + return Processing; // consumed some bytes, but message still not ready + } + else if (Elapsed(linkLayerTimeout) && currentScope != Scope::Stopped) { + return CommunicationTimeout; + } + return Processing; + } + + void ProtocolLogic::SendMsg(RequestMsg rq) { + #if defined(__AVR__) || defined(TARGET_LPC1768) + // Buddy FW cannot use stack-allocated txbuff - DMA doesn't work with CCMRAM + // No restrictions on MK3/S/+ though + uint8_t txbuff[Protocol::MaxRequestSize()]; + #endif + uint8_t len = Protocol::EncodeRequest(rq, txbuff); + #if defined(__AVR__) || defined(TARGET_LPC1768) + // TODO: I'm not sure if this is the correct approach with AVR + for ( uint8_t i = 0; i < len; i++) { + MMU_SERIAL.write(txbuff[i]); + } + #else + MMU_SERIAL.write(txbuff, len); + #endif + LogRequestMsg(txbuff, len); + RecordUARTActivity(); + } + + void ProtocolLogic::SendWriteMsg(RequestMsg rq) { + #if defined(__AVR__) || defined(TARGET_LPC1768) + // Buddy FW cannot use stack-allocated txbuff - DMA doesn't work with CCMRAM + // No restrictions on MK3/S/+ though + uint8_t txbuff[Protocol::MaxRequestSize()]; + #endif + uint8_t len = Protocol::EncodeWriteRequest(rq.value, rq.value2, txbuff); + + #if defined(__AVR__) || defined(TARGET_LPC1768) + // TODO: I'm not sure if this is the correct approach with AVR + for ( uint8_t i = 0; i < len; i++) { + MMU_SERIAL.write(txbuff[i]); + } + #else + MMU_SERIAL.write(txbuff, len); + #endif + LogRequestMsg(txbuff, len); + RecordUARTActivity(); + } + + void ProtocolLogic::StartSeqRestart() { + retries = maxRetries; + SendVersion(0); + } + + void ProtocolLogic::DelayedRestartRestart() { + scopeState = ScopeState::RecoveringProtocolError; + } + + void ProtocolLogic::CommandRestart() { + scopeState = ScopeState::CommandSent; + SendMsg(rq); + } + + void ProtocolLogic::IdleRestart() { + scopeState = ScopeState::Ready; + } + + StepStatus ProtocolLogic::ProcessVersionResponse(uint8_t stage) { + if (rsp.request.code != RequestMsgCodes::Version || rsp.request.value != stage) { + // got a response to something else - protocol corruption probably, repeat the query OR restart the comm by issuing S0? + SendVersion(stage); + } + else { + mmuFwVersion[stage] = rsp.paramValue; + if (mmuFwVersion[stage] != pgm_read_byte(&supportedMmuFWVersion[stage])) { + if (--retries == 0) return VersionMismatch; + SendVersion(stage); + } + else { + ResetCommunicationTimeoutAttempts(); // got a meaningful response from the MMU, stop data layer timeout tracking + SendVersion(stage + 1); + } + } + return Processing; + } + + StepStatus ProtocolLogic::ScopeStep() { + if (!ExpectsResponse()) { + // we are waiting for something + switch (currentScope) { + case Scope::DelayedRestart: + return DelayedRestartWait(); + case Scope::Idle: + return IdleWait(); + case Scope::Command: + return CommandWait(); + case Scope::Stopped: + return StoppedStep(); + default: + break; + } + } + else { + // we are expecting a message + auto expmsg = ExpectingMessage(); + if (expmsg != MessageReady) + return expmsg; + + // process message + switch (currentScope) { + case Scope::StartSeq: + return StartSeqStep(); // ~270B + case Scope::Idle: + return IdleStep(); // ~300B + case Scope::Command: + return CommandStep(); // ~430B + case Scope::Stopped: + return StoppedStep(); + default: + break; + } + } + return Finished; + } + + StepStatus ProtocolLogic::StartSeqStep() { + // solve initial handshake + switch (scopeState) { + case ScopeState::S0Sent: // received response to S0 - major + case ScopeState::S1Sent: // received response to S1 - minor + case ScopeState::S2Sent: // received response to S2 - patch + return ProcessVersionResponse((uint8_t)scopeState - (uint8_t)ScopeState::S0Sent); + case ScopeState::S3Sent: // received response to S3 - revision + if (rsp.request.code != RequestMsgCodes::Version || rsp.request.value != 3) { + // got a response to something else - protocol corruption probably, repeat the query OR restart the comm by issuing S0? + SendVersion(3); + } + else { + mmuFwVersionBuild = rsp.paramValue; // just register the build number + // Start General Interrogation after line up - initial parametrization is started + StartWritingInitRegisters(); + } + return Processing; + case ScopeState::WritingInitRegisters: + if (ProcessWritingInitRegister()) + SendAndUpdateFilamentSensor(); + return Processing; + case ScopeState::FilamentSensorStateSent: + SwitchFromStartToIdle(); + return Processing; // Returning Finished is not a good idea in case of a fast error recovery + // - it tells the printer, that the command which experienced a protocol error and recovered successfully actually terminated. + // In such a case we must return "Processing" in order to keep the MMU state machine running and prevent the printer from executing next G-codes. + default: + return VersionMismatch; + } + } + + StepStatus ProtocolLogic::DelayedRestartWait() { + if (Elapsed(heartBeatPeriod)) { // this basically means, that we are waiting until there is some traffic on + while (MMU_SERIAL.read() != -1); // clear the input buffer + // switch to StartSeq + start(); + } + return Processing; + } + + StepStatus ProtocolLogic::CommandWait() { + if (Elapsed(heartBeatPeriod)) + SendQuery(); + else + // even when waiting for a query period, we need to report a change in filament sensor's state + // - it is vital for a precise synchronization of moves of the printer and the MMU + CheckAndReportAsyncEvents(); + return Processing; + } + + StepStatus ProtocolLogic::ProcessCommandQueryResponse() { + switch (rsp.paramCode) { + case ResponseMsgParamCodes::Processing: + progressCode = static_cast(rsp.paramValue); + errorCode = ErrorCode::OK; + SendAndUpdateFilamentSensor(); // keep on reporting the state of fsensor regularly + return Processing; + case ResponseMsgParamCodes::Error: + // in case of an error the progress code remains as it has been before + progressCode = ProgressCode::ERRWaitingForUser; + errorCode = static_cast(rsp.paramValue); + // keep on reporting the state of fsensor regularly even in command error state + // - the MMU checks FINDA and fsensor even while recovering from errors + SendAndUpdateFilamentSensor(); + return CommandError; + case ResponseMsgParamCodes::Button: + // The user pushed a button on the MMU. Save it, do what we need to do + // to prepare, then pass it back to the MMU so it can work its magic. + buttonCode = static_cast(rsp.paramValue); + SendAndUpdateFilamentSensor(); + return ButtonPushed; + case ResponseMsgParamCodes::Finished: + // We must check whether the "finished" is actually related to the command issued into the MMU + // It can also be an X0 F which means MMU just successfully restarted. + if (ReqMsg().code == rsp.request.code && ReqMsg().value == rsp.request.value) { + progressCode = ProgressCode::OK; + errorCode = ErrorCode::OK; + scopeState = ScopeState::Ready; + rq = RequestMsg(RequestMsgCodes::unknown, 0); // clear the successfully finished request + return Finished; + } + else { + // got response to some other command - the originally issued command was interrupted! + return Interrupted; + } + default: + return ProtocolError; + } + } + + StepStatus ProtocolLogic::CommandStep() { + switch (scopeState) { + case ScopeState::CommandSent: { + switch (rsp.paramCode) { // the response should be either accepted or rejected + case ResponseMsgParamCodes::Accepted: + progressCode = ProgressCode::OK; + errorCode = ErrorCode::RUNNING; + scopeState = ScopeState::Wait; + break; + case ResponseMsgParamCodes::Rejected: + // rejected - should normally not happen, but report the error up + progressCode = ProgressCode::OK; + errorCode = ErrorCode::PROTOCOL_ERROR; + return CommandRejected; + default: + return ProtocolError; + } + } + break; + case ScopeState::QuerySent: + return ProcessCommandQueryResponse(); + case ScopeState::FilamentSensorStateSent: + StartReading8bitRegisters(); + return Processing; + case ScopeState::Reading8bitRegisters: + ProcessRead8bitRegister(); + return Processing; + case ScopeState::Reading16bitRegisters: + scopeState = ProcessRead16bitRegister(ScopeState::Wait); + return Processing; + case ScopeState::ButtonSent: + if (rsp.paramCode == ResponseMsgParamCodes::Accepted) + // Button was accepted, decrement the retry. + DecrementRetryAttempts(); + SendAndUpdateFilamentSensor(); + break; + default: + return ProtocolError; + } + return Processing; + } + + StepStatus ProtocolLogic::IdleWait() { + if (scopeState == ScopeState::Ready) { // check timeout + if (Elapsed(heartBeatPeriod)) { + SendQuery(); + return Processing; + } + } + return Finished; + } + + StepStatus ProtocolLogic::IdleStep() { + switch (scopeState) { + case ScopeState::QuerySent: // check UART + // If we are accidentally in Idle and we receive something like "T0 P1" - that means the communication dropped out while a command was in progress. + // That causes no issues here, we just need to switch to Command processing and continue there from now on. + // The usual response in this case should be some command and "F" - finished - that confirms we are in an Idle state even on the MMU side. + switch (rsp.request.code) { + case RequestMsgCodes::Cut: + case RequestMsgCodes::Eject: + case RequestMsgCodes::Load: + case RequestMsgCodes::Mode: + case RequestMsgCodes::Tool: + case RequestMsgCodes::Unload: + if (rsp.paramCode != ResponseMsgParamCodes::Finished) + return SwitchFromIdleToCommand(); + break; + case RequestMsgCodes::Reset: + // this one is kind of special + // we do not transfer to any "running" command (i.e. we stay in Idle), + // but in case there is an error reported we must make sure it gets propagated + switch (rsp.paramCode) { + case ResponseMsgParamCodes::Button: + // The user pushed a button on the MMU. Save it, do what we need to do + // to prepare, then pass it back to the MMU so it can work its magic. + buttonCode = static_cast(rsp.paramValue); + StartReading8bitRegisters(); + return ButtonPushed; + case ResponseMsgParamCodes::Finished: + if (ReqMsg().code != RequestMsgCodes::unknown) { + // got reset while doing some other command - the originally issued command was interrupted! + // this must be solved by the upper layer, protocol logic doesn't have all the context (like unload before trying again) + IdleRestart(); + return Interrupted; + } + // [[fallthrough]]; + // fall through + case ResponseMsgParamCodes::Processing: + // @@TODO we may actually use this branch to report progress of manual operation on the MMU + // The MMU sends e.g. X0 P27 after its restart when the user presses an MMU button to move the Selector + progressCode = static_cast(rsp.paramValue); + errorCode = ErrorCode::OK; + break; + default: + progressCode = ProgressCode::ERRWaitingForUser; + errorCode = static_cast(rsp.paramValue); + StartReading8bitRegisters(); // continue Idle state without restarting the communication + return CommandError; + } + break; + default: + return ProtocolError; + } + StartReading8bitRegisters(); + return Processing; + case ScopeState::Reading8bitRegisters: + ProcessRead8bitRegister(); + return Processing; + case ScopeState::Reading16bitRegisters: + scopeState = ProcessRead16bitRegister(ScopeState::Ready); + return scopeState == ScopeState::Ready ? Finished : Processing; + case ScopeState::ButtonSent: + if (rsp.paramCode == ResponseMsgParamCodes::Accepted) + // Button was accepted, decrement the retry. + DecrementRetryAttempts(); + StartReading8bitRegisters(); + return Processing; + case ScopeState::ReadRegisterSent: + if (rsp.paramCode == ResponseMsgParamCodes::Accepted) { + // @@TODO just dump the value onto the serial + } + return Finished; + case ScopeState::WriteRegisterSent: + if (rsp.paramCode == ResponseMsgParamCodes::Accepted) { + // @@TODO do something? Retry if not accepted? + } + return Finished; + default: + return ProtocolError; + } + + // The "return Finished" in this state machine requires a bit of explanation: + // The Idle state either did nothing (still waiting for the heartbeat timeout) + // or just successfully received the answer to Q0, whatever that was. + // In both cases, it is ready to hand over work to a command or something else, + // therefore we are returning Finished (also to exit mmu_loop() and unblock Marlin's loop!). + // If there is no work, we'll end up in the Idle state again + // and we'll send the heartbeat message after the specified timeout. + return Finished; + } + + ProtocolLogic::ProtocolLogic(uint8_t extraLoadDistance, uint8_t pulleySlowFeedrate) + : explicitPrinterError(ErrorCode::OK) + , currentScope(Scope::Stopped) + , scopeState(ScopeState::Ready) + , plannedRq(RequestMsgCodes::unknown, 0) + , lastUARTActivityMs(0) + , dataTO() + , rsp(RequestMsg(RequestMsgCodes::unknown, 0), ResponseMsgParamCodes::unknown, 0) + , state(State::Stopped) + , lrb(0) + , errorCode(ErrorCode::OK) + , progressCode(ProgressCode::OK) + , buttonCode(Buttons::NoButton) + , lastFSensor((uint8_t)WhereIsFilament()) + , regIndex(0) + , retryAttempts(MMU3_MAX_RETRIES) + , inAutoRetry(false) { + // @@TODO currently, I don't see a way of writing the initialization better :( + // I'd like to write something like: initRegs8 { extraLoadDistance, pulleySlowFeedrate } + // avr-gcc seems to like such a syntax, ARM gcc doesn't + initRegs8[0] = extraLoadDistance; + initRegs8[1] = pulleySlowFeedrate; + } + + void ProtocolLogic::start() { + state = State::InitSequence; + currentScope = Scope::StartSeq; + protocol.ResetResponseDecoder(); // important - finished delayed restart relies on this + StartSeqRestart(); + } + + void ProtocolLogic::stop() { + state = State::Stopped; + currentScope = Scope::Stopped; + } + + void ProtocolLogic::ToolChange(uint8_t slot) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Tool, slot)); + } + + void ProtocolLogic::Statistics() { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Version, 3)); + } + + void ProtocolLogic::UnloadFilament() { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Unload, 0)); + } + + void ProtocolLogic::LoadFilament(uint8_t slot) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Load, slot)); + } + + void ProtocolLogic::EjectFilament(uint8_t slot) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Eject, slot)); + } + + void ProtocolLogic::CutFilament(uint8_t slot) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Cut, slot)); + } + + void ProtocolLogic::ResetMMU(uint8_t mode /* = 0 */) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Reset, mode)); + } + + void ProtocolLogic::button(uint8_t index) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Button, index)); + } + + void ProtocolLogic::home(uint8_t mode) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Home, mode)); + } + + void ProtocolLogic::readRegister(uint8_t address) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Read, address)); + } + + void ProtocolLogic::writeRegister(uint8_t address, uint16_t data) { + PlanGenericRequest(RequestMsg(RequestMsgCodes::Write, address, data)); + } + + void ProtocolLogic::PlanGenericRequest(RequestMsg rq) { + plannedRq = rq; + if (!ExpectsResponse()) + ActivatePlannedRequest(); + // otherwise wait for an empty window to activate the request + } + + bool ProtocolLogic::ActivatePlannedRequest() { + switch (plannedRq.code) { + case RequestMsgCodes::Button: + // only issue the button to the MMU and do not restart the state machines + SendButton(plannedRq.value); + plannedRq = RequestMsg(RequestMsgCodes::unknown, 0); + return true; + case RequestMsgCodes::Read: + SendReadRegister(plannedRq.value, ScopeState::ReadRegisterSent); + plannedRq = RequestMsg(RequestMsgCodes::unknown, 0); + return true; + case RequestMsgCodes::Write: + SendWriteRegister(plannedRq.value, plannedRq.value2, ScopeState::WriteRegisterSent); + plannedRq = RequestMsg(RequestMsgCodes::unknown, 0); + return true; + case RequestMsgCodes::unknown: + return false; + default: // commands + currentScope = Scope::Command; + SetRequestMsg(plannedRq); + plannedRq = RequestMsg(RequestMsgCodes::unknown, 0); + CommandRestart(); + return true; + } + } + + StepStatus ProtocolLogic::SwitchFromIdleToCommand() { + currentScope = Scope::Command; + SetRequestMsg(rsp.request); + // we are recovering from a communication drop out, the command is already running + // and we have just received a response to a Q0 message about a command progress + return ProcessCommandQueryResponse(); + } + + void ProtocolLogic::SwitchToIdle() { + state = State::Running; + currentScope = Scope::Idle; + IdleRestart(); + } + + void ProtocolLogic::SwitchFromStartToIdle() { + state = State::Running; + currentScope = Scope::Idle; + IdleRestart(); + SendQuery(); // force sending Q0 immediately + } + + bool ProtocolLogic::Elapsed(uint32_t timeout) const { + return ELAPSED(_millis(), lastUARTActivityMs + timeout); + } + + void ProtocolLogic::RecordUARTActivity() { + lastUARTActivityMs = _millis(); + } + + void ProtocolLogic::RecordReceivedByte(uint8_t c) { + lastReceivedBytes[lrb] = c; + lrb = (lrb + 1) % COUNT(lastReceivedBytes); + } + + constexpr char NibbleToChar(uint8_t c) { + switch (c) { + case 0x0 ... 0x9: return c + '0'; + case 0xA ... 0xF: return (c - 10) + 'a'; + default: return 0; + } + } + + void ProtocolLogic::FormatLastReceivedBytes(char *dst) { + for (uint8_t i = 0; i < COUNT(lastReceivedBytes); ++i) { + uint8_t b = lastReceivedBytes[(COUNT(lastReceivedBytes) - 1 + (lrb - i)) % COUNT(lastReceivedBytes)]; + dst[i * 3] = NibbleToChar(b >> 4); + dst[i * 3 + 1] = NibbleToChar(b & 0xf); + dst[i * 3 + 2] = ' '; + } + dst[(COUNT(lastReceivedBytes) - 1) * 3 + 2] = 0; // terminate properly + } + + void ProtocolLogic::FormatLastResponseMsgAndClearLRB(char *dst) { + *dst++ = '<'; + for (uint8_t i = 0; i < lrb; ++i) { + uint8_t b = lastReceivedBytes[i]; + // Check for printable character, including space + if (b < 32 || b > 127) + b = '.'; + *dst++ = b; + } + *dst = 0; // terminate properly + lrb = 0; // reset the input buffer index in case of a clean message + } + + void ProtocolLogic::LogRequestMsg(const uint8_t *txbuff, uint8_t size) { + constexpr uint_fast8_t rqs = modules::protocol::Protocol::MaxRequestSize() + 1; + char tmp[rqs] = ">"; + static char lastMsg[rqs] = ""; + for (uint8_t i = 0; i < size; ++i) { + uint8_t b = txbuff[i]; + // Check for printable character, including space + if (b < 32 || b > 127) + b = '.'; + tmp[i + 1] = b; + } + tmp[size + 1] = 0; + if (!strncmp_P(tmp, PSTR(">S0*c6."), rqs) && !strncmp(lastMsg, tmp, rqs)) { + // @@TODO we skip the repeated request msgs for now + // to avoid spoiling the whole log just with ">S0" messages + // especially when the MMU is not connected. + // We'll lose the ability to see if the printer is actually + // trying to find the MMU, but since it has been reliable in the past + // we can live without it for now. + } + else { + MMU2_ECHO_MSGLN(tmp); + } + strncpy(lastMsg, tmp, rqs); + } + + void ProtocolLogic::LogError(const char *reason_P) { + char _lrb[COUNT(lastReceivedBytes) * 3]; + FormatLastReceivedBytes(_lrb); + + MMU2_ERROR_MSGRPGM(reason_P); + SERIAL_ECHOPGM(", last bytes: "); + SERIAL_ECHOLN(_lrb); + } + + void ProtocolLogic::LogResponse() { + char _lrb[COUNT(lastReceivedBytes)]; + FormatLastResponseMsgAndClearLRB(_lrb); + MMU2_ECHO_MSGLN(_lrb); + } + + StepStatus ProtocolLogic::SuppressShortDropOuts(const char *msg_P, StepStatus ss) { + if (dataTO.Record(ss)) { + LogError(msg_P); + ResetCommunicationTimeoutAttempts(); // prepare for another run of consecutive retries before firing an error + return dataTO.InitialCause(); + } + else { + return Processing; // suppress short drop outs of communication + } + } + + StepStatus ProtocolLogic::HandleCommunicationTimeout() { + MMU_SERIAL.flush(); // clear the output buffer + protocol.ResetResponseDecoder(); + start(); + return SuppressShortDropOuts(PSTR("Communication timeout"), CommunicationTimeout); + } + + StepStatus ProtocolLogic::HandleProtocolError() { + MMU_SERIAL.flush(); // clear the output buffer + state = State::InitSequence; + currentScope = Scope::DelayedRestart; + DelayedRestartRestart(); + return SuppressShortDropOuts(PSTR("Protocol Error"), ProtocolError); + } + + StepStatus ProtocolLogic::Step() { + if (!ExpectsResponse()) // if not waiting for a response, activate a planned request immediately + ActivatePlannedRequest(); + auto currentStatus = ScopeStep(); + switch (currentStatus) { + case Processing: + // we are ok, the state machine continues correctly + break; + case Finished: { + // We are ok, switching to Idle if there is no potential next request planned. + // But the trouble is we must report a finished command if the previous command has just been finished + // i.e. only try to find some planned command if we just finished the Idle cycle + if (!ActivatePlannedRequest()) { // if nothing is planned, switch to Idle + SwitchToIdle(); + } + else if (ExpectsResponse()) { + // if the previous cycle was Idle and now we have planned a new command -> avoid returning Finished + currentStatus = Processing; + } + } + break; + case CommandRejected: + // we have to repeat it - that's the only thing we can do + // no change in state + // @@TODO wait until Q0 returns command in progress finished, then we can send this one + LogError(PSTR("Command rejected")); + CommandRestart(); + break; + case CommandError: + LogError(PSTR("Command Error")); + // we should probably transfer into the Idle state and await further instructions from the upper layer + // Idle state may solve the problem of keeping up the heart beat running + break; + case VersionMismatch: + LogError(PSTR("Version mismatch")); + break; + case ProtocolError: + currentStatus = HandleProtocolError(); + break; + case CommunicationTimeout: + currentStatus = HandleCommunicationTimeout(); + break; + default: + break; + } + // special handling of explicit printer errors + return IsPrinterError() ? StepStatus::PrinterError : currentStatus; + } + + uint8_t ProtocolLogic::CommandInProgress() const { + if (currentScope != Scope::Command) return 0; + return (uint8_t)ReqMsg().code; + } + + void ProtocolLogic::DecrementRetryAttempts() { + if (inAutoRetry && retryAttempts) { + SERIAL_ECHOLNPGM("DecrementRetryAttempts"); + retryAttempts--; + } + } + + void ProtocolLogic::ResetRetryAttempts() { + SERIAL_ECHOLNPGM("ResetRetryAttempts"); + retryAttempts = MMU3_MAX_RETRIES; + } + + void __attribute__((noinline)) ProtocolLogic::ResetCommunicationTimeoutAttempts() { + SERIAL_ECHOLNPGM("RSTCommTimeout"); + dataTO.reset(); + } + + bool DropOutFilter::Record(StepStatus ss) { + if (occurrences == maxOccurrences) cause = ss; + --occurrences; + return occurrences == 0; + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_protocol_logic.h b/Marlin/src/feature/mmu3/mmu3_protocol_logic.h new file mode 100644 index 0000000000..30f9c5d0d5 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_protocol_logic.h @@ -0,0 +1,380 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_protocol_logic.h + */ + +#include "../../MarlinCore.h" + +#include + +#ifdef __AVR__ + #include + #include "mmu_hw/error_codes.h" + #include "mmu_hw/progress_codes.h" + #include "mmu_hw/buttons.h" + #include "mmu_hw/registers.h" + #include "mmu3_protocol.h" +#else // !__AVR__ + + #include "mmu_hw/error_codes.h" + #include "mmu_hw/progress_codes.h" + + // Prevent ARM HAL macros from breaking our code + #undef CRC + #include "mmu3_protocol.h" + #include "mmu_hw/buttons.h" + #include "registers.h" + +#endif // !__AVR__ + +// New MMU3 protocol logic +namespace MMU3 { + + using namespace modules::protocol; + + class ProtocolLogic; + + // ProtocolLogic stepping statuses + enum StepStatus : uint_fast8_t { + Processing = 0, + MessageReady, //!< A message has been successfully decoded from the received bytes + Finished, //!< Scope finished successfully + Interrupted, //!< Received "Finished" message related to a different command than originally issued (most likely the MMU restarted while doing something) + CommunicationTimeout, //!< The MMU failed to respond to a request within a specified time frame + ProtocolError, //!< Bytes read from the MMU didn't form a valid response + CommandRejected, //!< The MMU rejected the command due to some other command in progress, may be the user is operating the MMU locally (button commands) + CommandError, //!< The command in progress stopped due to unrecoverable error, user interaction required + VersionMismatch, //!< The MMU reports its firmware version incompatible with our implementation + PrinterError, //!< Printer's explicit error - MMU is fine, but the printer was unable to complete the requested operation + CommunicationRecovered, + ButtonPushed //!< The MMU reported the user pushed one of its three buttons. + }; + + /*inline*/ constexpr uint32_t linkLayerTimeout = 2000; //!< Default link layer communication timeout + /*inline*/ constexpr uint32_t dataLayerTimeout = linkLayerTimeout * 3; //!< Data layer communication timeout + /*inline*/ constexpr uint32_t heartBeatPeriod = linkLayerTimeout / 2; //!< Period of heart beat messages (Q0) + + static_assert(heartBeatPeriod < linkLayerTimeout && linkLayerTimeout < dataLayerTimeout, "Incorrect ordering of timeouts"); + + //!< Filter of short consecutive drop outs which are recovered instantly + class DropOutFilter { + public: + static constexpr uint8_t maxOccurrences = 10; // ideally set this to >8 seconds -> 12x heartBeatPeriod + static_assert(maxOccurrences > 1, "we should really silently ignore at least 1 comm drop out if recovered immediately afterwards"); + DropOutFilter() = default; + + // @return true if the error should be reported to higher levels (max. number of consecutive occurrences reached) + bool Record(StepStatus ss); + + // @return the initial cause which started this drop out event + inline StepStatus InitialCause() const { return cause; } + + // Rearms the object for further processing - basically call this once the MMU responds with something meaningful (e.g. S0 A2) + inline void reset() { occurrences = maxOccurrences; } + + private: + StepStatus cause; + uint8_t occurrences = maxOccurrences; + }; + + // Logic layer of the MMU vs. printer communication protocol + class ProtocolLogic { + public: + ProtocolLogic(uint8_t extraLoadDistance, uint8_t pulleySlowFeedrate); + + // Start/Enable communication with the MMU + void start(); + + // Stop/Disable communication with the MMU + void stop(); + + // Issue commands to the MMU + void ToolChange(uint8_t slot); + void Statistics(); + void UnloadFilament(); + void LoadFilament(uint8_t slot); + void EjectFilament(uint8_t slot); + void CutFilament(uint8_t slot); + void ResetMMU(uint8_t mode=0); + void button(uint8_t index); + void home(uint8_t mode); + void readRegister(uint8_t address); + void writeRegister(uint8_t address, uint16_t data); + + // Set the extra load distance to be reported to the MMU. + // Beware - this call doesn't send anything to the MMU. + // The MMU gets the newly set value either by a communication restart or via an explicit writeRegister call + inline void PlanExtraLoadDistance(uint8_t eld_mm) { initRegs8[0] = eld_mm; } + // @return the currently preset extra load distance + inline uint8_t ExtraLoadDistance() const { return initRegs8[0]; } + + // Sets the Pulley slow feed rate to be reported to the MMU. + // Beware - this call doesn't send anything to the MMU. + // The MMU gets the newly set value either by a communication restart or via an explicit writeRegister call + inline void PlanPulleySlowFeedRate(uint8_t psfr) { + initRegs8[1] = psfr; + } + // @return the currently preset Pulley slow feed rate + inline uint8_t PulleySlowFeedRate() const { + return initRegs8[1]; // even though MMU register 0x14 is 16bit, reasonable speeds are way below 255mm/s - saving space ;) + } + + // Step the state machine + StepStatus Step(); + + // @return the current/latest error code as reported by the MMU + ErrorCode Error() const { return errorCode; } + + // @return the current/latest process code as reported by the MMU + ProgressCode Progress() const { return progressCode; } + + // @return the current/latest button code as reported by the MMU + Buttons button() const { return buttonCode; } + + uint8_t CommandInProgress() const; + + inline bool Running() const { return state == State::Running; } + + inline bool findaPressed() const { return regs8[0]; } + + inline uint16_t FailStatistics() const { return regs16[0]; } + + inline uint8_t mmuFwVersionMajor() const { return mmuFwVersion[0]; } + inline uint8_t mmuFwVersionMinor() const { return mmuFwVersion[1]; } + inline uint8_t mmuFwVersionRevision() const { return mmuFwVersion[2]; } + + // Current number of retry attempts left + constexpr uint8_t RetryAttempts() const { return retryAttempts; } + + // Decrement the retry attempts, if in a retry. + // Called by the MMU protocol when a sent button is acknowledged. + void DecrementRetryAttempts(); + + // Reset the retryAttempts back to the default value + void ResetRetryAttempts(); + + void ResetCommunicationTimeoutAttempts(); + + constexpr bool InAutoRetry() const { return inAutoRetry; } + inline void SetInAutoRetry(const bool iar) { inAutoRetry = iar; } + + inline void SetPrinterError(const ErrorCode ec) { explicitPrinterError = ec; } + inline void clearPrinterError() { explicitPrinterError = ErrorCode::OK; } + inline bool IsPrinterError() const { return explicitPrinterError != ErrorCode::OK; } + inline ErrorCode PrinterError() const { return explicitPrinterError; } + + #ifndef UNITTEST + private: + #endif + + StepStatus ExpectingMessage(); + void SendMsg(RequestMsg rq); + void SendWriteMsg(RequestMsg rq); + void SwitchToIdle(); + StepStatus SuppressShortDropOuts(const char *msg_P, StepStatus ss); + StepStatus HandleCommunicationTimeout(); + StepStatus HandleProtocolError(); + bool Elapsed(uint32_t timeout) const; + void RecordUARTActivity(); + void RecordReceivedByte(uint8_t c); + void FormatLastReceivedBytes(char *dst); + void FormatLastResponseMsgAndClearLRB(char *dst); + void LogRequestMsg(const uint8_t *txbuff, uint8_t size); + void LogError(const char *reason_P); + void LogResponse(); + StepStatus SwitchFromIdleToCommand(); + void SwitchFromStartToIdle(); + + ErrorCode explicitPrinterError; + + enum class State : uint_fast8_t { + Stopped, //!< stopped for whatever reason + InitSequence, //!< initial sequence running + Running //!< normal operation - Idle + Command processing + }; + + enum class Scope : uint_fast8_t { + Stopped, + StartSeq, + DelayedRestart, + Idle, + Command + }; + Scope currentScope; + + // basic scope members + // @return true if the state machine is waiting for a response from the MMU + bool ExpectsResponse() const { return ((uint8_t)scopeState & (uint8_t)ScopeState::NotExpectsResponse) == 0; } + + // Common internal states of the derived sub-automata + // General rule of thumb: *Sent states are waiting for a response from the MMU + enum class ScopeState : uint_fast8_t { + S0Sent, // beware - due to optimization reasons these SxSent must be kept one after another + S1Sent, + S2Sent, + S3Sent, + QuerySent, + CommandSent, + FilamentSensorStateSent, + Reading8bitRegisters, + Reading16bitRegisters, + WritingInitRegisters, + ButtonSent, + ReadRegisterSent, // standalone requests for reading registers - from higher layers + WriteRegisterSent, + + // States which do not expect a message - MSb set + NotExpectsResponse = 0x80, + Wait = NotExpectsResponse + 1, + Ready = NotExpectsResponse + 2, + RecoveringProtocolError = NotExpectsResponse + 3, + }; + + ScopeState scopeState; //!< internal state of the sub-automaton + + // @return the status of processing of the FINDA query response + // @param finishedRV returned value in case the message was successfully received and processed + // @param nextState is a state where the state machine should transfer to after the message was successfully received and processed + // StepStatus ProcessFINDAReqSent(StepStatus finishedRV, State nextState); + + // @return the status of processing of the statistics query response + // @param finishedRV returned value in case the message was successfully received and processed + // @param nextState is a state where the state machine should transfer to after the message was successfully received and processed + // StepStatus ProcessStatisticsReqSent(StepStatus finishedRV, State nextState); + + // Called repeatedly while waiting for a query (Q0) period. + // All event checks to report immediately from the printer to the MMU should be done in this method. + // So far, the only such a case is the filament sensor, but there can be more like this in the future. + void CheckAndReportAsyncEvents(); + void SendQuery(); + void StartReading8bitRegisters(); + void ProcessRead8bitRegister(); + void StartReading16bitRegisters(); + ScopeState ProcessRead16bitRegister(ProtocolLogic::ScopeState stateAtEnd); + void StartWritingInitRegisters(); + // @return true when all registers have been written into the MMU + bool ProcessWritingInitRegister(); + void SendAndUpdateFilamentSensor(); + void SendButton(uint8_t btn); + void SendVersion(uint8_t stage); + void SendReadRegister(uint8_t index, ScopeState nextState); + void SendWriteRegister(uint8_t index, uint16_t value, ScopeState nextState); + + StepStatus ProcessVersionResponse(uint8_t stage); + + // Top level split - calls the appropriate step based on current scope + StepStatus ScopeStep(); + + static constexpr uint8_t maxRetries = 6; + uint8_t retries; + + void StartSeqRestart(); + void DelayedRestartRestart(); + void IdleRestart(); + void CommandRestart(); + + StepStatus StartSeqStep(); + StepStatus DelayedRestartWait(); + StepStatus IdleStep(); + StepStatus IdleWait(); + StepStatus CommandStep(); + StepStatus CommandWait(); + StepStatus StoppedStep() { return Processing; } + + StepStatus ProcessCommandQueryResponse(); + + inline void SetRequestMsg(const RequestMsg msg) { rq = msg; } + inline const RequestMsg &ReqMsg() const { return rq; } + RequestMsg rq = RequestMsg(RequestMsgCodes::unknown, 0); + + // Records the next planned state, "unknown" msg code if no command is planned. + // This is not intended to be a queue of commands to process, protocol_logic must not queue commands. + // It exists solely to prevent breaking the Request-Response protocol handshake - + // - during tests it turned out, that the commands from Marlin are coming in such an asynchronnous way, that + // we could accidentally send T2 immediately after Q0 without waiting for reception of response to Q0. + // + // Beware, if Marlin manages to call PlanGenericCommand multiple times before a response comes, + // these variables will get overwritten by the last call. + // However, that should not happen under normal circumstances as Marlin should wait for the Command to finish, + // which includes all responses (and error recovery if any). + RequestMsg plannedRq; + + // Plan a command to be processed once the immediate response to a sent request arrives + void PlanGenericRequest(RequestMsg rq); + // Activate the planned state once the immediate response to a sent request arrived + bool ActivatePlannedRequest(); + + uint32_t lastUARTActivityMs; //!< timestamp - last ms when something occurred on the UART + DropOutFilter dataTO; //!< Filter of short consecutive drop outs which are recovered instantly + + ResponseMsg rsp; //!< decoded response message from the MMU protocol + + State state; //!< internal state of ProtocolLogic + + Protocol protocol; //!< protocol codec + + uint8_t lrb, lastReceivedBytes[16]; //!< keep the last few bytes of incoming communication for diagnostic purposes + + ErrorCode errorCode; //!< last received error code from the MMU + ProgressCode progressCode; //!< last received progress code from the MMU + Buttons buttonCode; //!< Last received button from the MMU. + + uint8_t lastFSensor; //!< last state of filament sensor + + #ifndef __AVR__ + uint8_t txbuff[Protocol::MaxRequestSize()]; //!< In Buddy FW - a static transmit buffer needs to exist as DMA cannot be used from CCMRAM. + //!< On MK3/S/+ the transmit buffer is allocated on the stack without restrictions + #endif + + // 8bit registers + static constexpr uint8_t regs8Count = 3; + static_assert(regs8Count > 0); // code is not ready for empty lists of registers + static const Register regs8Addrs[regs8Count] PROGMEM; + uint8_t regs8[regs8Count] = { 0, 0, 0 }; + + // 16bit registers + static constexpr uint8_t regs16Count = 2; + static_assert(regs16Count > 0); // code is not ready for empty lists of registers + static const Register regs16Addrs[regs16Count] PROGMEM; + uint16_t regs16[regs16Count] = { 0, 0 }; + + // 8bit init values to be sent to the MMU after line up + static constexpr uint8_t initRegs8Count = 2; + static_assert(initRegs8Count > 0); // code is not ready for empty lists of registers + static const Register initRegs8Addrs[initRegs8Count] PROGMEM; + uint8_t initRegs8[initRegs8Count]; + + uint8_t regIndex; + + uint8_t mmuFwVersion[3] = { 0, 0, 0 }; + uint16_t mmuFwVersionBuild; + + uint8_t retryAttempts; + bool inAutoRetry; + + friend class MMU3; + }; + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_reporting.cpp b/Marlin/src/feature/mmu3/mmu3_reporting.cpp new file mode 100644 index 0000000000..c9b9dbe554 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_reporting.cpp @@ -0,0 +1,705 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * mmu2_reporting.cpp + */ + +#include "../../inc/MarlinConfig.h" + +#if HAS_PRUSA_MMU3 + +#include "mmu3.h" +#include "mmu3_log.h" +#include "mmu3_fsensor.h" +#include "mmu3_reporting.h" +#include "mmu3_error_converter.h" +#include "mmu3_marlin_macros.h" +#include "mmu3_progress_converter.h" +#include "mmu_hw/buttons.h" +#include "mmu_hw/error_codes.h" +#include "mmu_hw/errors_list.h" +#include "ultralcd.h" +#include "sound.h" + +#include "../../core/language.h" +#include "../../gcode/gcode.h" +#include "../host_actions.h" +#include "../../lcd/marlinui.h" +#include "../../lcd/menu/menu.h" +#include "../../lcd/menu/menu_item.h" +#include "../../module/temperature.h" + +namespace MMU3 { + + OperationStatistics operation_statistics; + + uint16_t OperationStatistics::fail_total_num; // total failures + uint8_t OperationStatistics::fail_num; // fails during print + uint16_t OperationStatistics::load_fail_total_num; // total load failures + uint8_t OperationStatistics::load_fail_num; // load failures during print + uint16_t OperationStatistics::tool_change_counter; // number of tool changes per print + uint32_t OperationStatistics::tool_change_total_counter; // number of total tool changes + int OperationStatistics::fail_total_num_addr; // total failures EEPROM addr + int OperationStatistics::fail_num_addr; // fails during print EEPROM addr + int OperationStatistics::load_fail_total_num_addr; // total load failures EEPROM addr + int OperationStatistics::load_fail_num_addr; // load failures during print EEPROM addr + int OperationStatistics::tool_change_counter_addr; // number of total tool changes EEPROM addr + int OperationStatistics::tool_change_total_counter_addr; // number of total tool changes EEPROM addr + + /** + * Increment both the total load fails and Per print job load fails. + */ + void OperationStatistics::increment_load_fails() { + load_fail_num += 1; + load_fail_total_num += 1; + + #if ENABLED(EEPROM_SETTINGS) + // save load_fail_num to eeprom + persistentStore.access_start(); + persistentStore.write_data(load_fail_num_addr, load_fail_num); + + // save load_fail_total_num to eeprom + persistentStore.write_data(load_fail_total_num_addr, load_fail_total_num); + persistentStore.access_finish(); + settings.save(); + #endif + } + + /** + * Increment both the total fails and the per print job fails. + */ + void OperationStatistics::increment_mmu_fails() { + fail_num += 1; + fail_total_num += 1; + + #if ENABLED(EEPROM_SETTINGS) + // save fail_num to eeprom + persistentStore.access_start(); + persistentStore.write_data(fail_num_addr, fail_num); + // save fail_total_num to eeprom + persistentStore.write_data(fail_total_num_addr, fail_total_num); + persistentStore.access_finish(); + settings.save(); + #endif + } + + /** + * Increment tool change counter + */ + void OperationStatistics::increment_tool_change_counter() { + tool_change_counter += 1; + tool_change_total_counter += 1; + + #if ENABLED(EEPROM_SETTINGS) + // save tool_change_total_counter to eeprom + persistentStore.access_start(); + persistentStore.write_data(tool_change_total_counter_addr, tool_change_total_counter); + persistentStore.access_finish(); + settings.save(); + #endif + } + + + /** + * Reset only per print operation statistics and update EEPROM. + * + * @return true if everything went okay, false otherwise. + */ + bool OperationStatistics::reset_per_print_stats() { + // Update data + load_fail_num = 0; + fail_num = 0; + tool_change_counter = 0; + + #if ENABLED(EEPROM_SETTINGS) + // Update EEPROM + persistentStore.access_start(); + persistentStore.write_data(load_fail_num_addr, load_fail_num); + persistentStore.write_data(fail_num_addr, fail_num); + persistentStore.write_data(tool_change_counter_addr, tool_change_counter); + persistentStore.access_finish(); + return settings.save(); + #else + return true; + #endif + } + + + /** + * Reset fail statistics and update EEPROM. + * + * This will keep the tool change counter change counters and delete anything + * else. + * + * @return true if everything went okay, false otherwise. + */ + bool OperationStatistics::reset_fail_stats() { + // Update data + load_fail_num = 0; + load_fail_total_num = 0; + fail_num = 0; + fail_total_num = 0; + + #if ENABLED(EEPROM_SETTINGS) + // Update EEPROM + persistentStore.access_start(); + persistentStore.write_data(load_fail_num_addr, load_fail_num); + persistentStore.write_data(load_fail_total_num_addr, load_fail_total_num); + persistentStore.write_data(fail_num_addr, fail_num); + persistentStore.write_data(fail_total_num_addr, fail_total_num); + persistentStore.access_finish(); + return settings.save(); + #else + return true; + #endif + } + + + /** + * Reset all operation statistics and update EEPROM. + * + * @return true if everything went okay, false otherwise. + */ + bool OperationStatistics::reset_stats() { + // Update data + load_fail_num = 0; + load_fail_total_num = 0; + fail_num = 0; + fail_total_num = 0; + tool_change_counter = 0; + tool_change_total_counter = 0; + + #if ENABLED(EEPROM_SETTINGS) + // Update EEPROM + persistentStore.access_start(); + persistentStore.write_data(load_fail_num_addr, load_fail_num); + persistentStore.write_data(load_fail_total_num_addr, load_fail_total_num); + persistentStore.write_data(fail_num_addr, fail_num); + persistentStore.write_data(fail_total_num_addr, fail_total_num); + persistentStore.write_data(tool_change_counter_addr, tool_change_counter); + persistentStore.write_data(tool_change_total_counter_addr, tool_change_total_counter); + persistentStore.access_finish(); + return settings.save(); + #else + return true; + #endif + } + + + void BeginReport(CommandInProgress /*cip*/, ProgressCode ec) { + // custom_message_type = CustomMsg::MMUProgress; + ui.set_status(ProgressCodeToText(ec)); + } + + void EndReport(CommandInProgress /*cip*/, ProgressCode /*ec*/) { + // clear the status msg line - let the printed filename get visible again + if (!marlin.printJobOngoing()) ui.reset_status(); + //custom_message_type = CustomMsg::Status; + } + + /** + * @brief Renders any characters that will be updated live on the MMU error screen. + *Currently, this is FINDA and Filament Sensor status and Extruder temperature. + */ + extern void ReportErrorHookDynamicRender(void) { + #if HAS_WIRED_LCD + // beware - this optimization abuses the fact, that findaDetectsFilament returns 0 or 1 and '0' is followed by '1' in the ASCII table + lcd_put_int(3, LCD_HEIGHT - 1, mmu3.findaDetectsFilament() + '0'); + lcd_put_int(8, LCD_HEIGHT - 1, FILAMENT_PRESENT() + '0'); + + // print active/changing filament slot + lcd_moveto(10, LCD_HEIGHT - 1); + lcdui_print_extruder(); + + // Print active extruder temperature + lcd_put_int(16, LCD_HEIGHT - 1, (int)(thermalManager.degHotend(0) + 0.5)); + #endif + } + + static bool drawing_more_info_screen = false; + static bool msg_next_is_consumed = false; + static FSTR_P msg_next = nullptr; + + /** + * Display more info about the error. If the error message doesn't fit into + * the screen, clicking the LCD button will go to the next screen to display + * the rest of the message, until no messages left to display and a final + * click will return to the previous screen. + * + * This gets the message data from the "editable.uint8" which is set in the + * action item. + */ + void show_more_info_screen() { + #if HAS_WIRED_LCD + if (drawing_more_info_screen) return; + drawing_more_info_screen = true; + FSTR_P fmsg = PrusaErrorDesc(editable.uint8); + if (ui.use_click()) { + if (msg_next_is_consumed) { + msg_next_is_consumed = false; + drawing_more_info_screen = false; + msg_next = nullptr; + // Prevent this function being triggered again... + SetButtonResponse(ButtonOperations::NoOperation); + return ui.go_back(); + } + fmsg = msg_next; + } + else if (msg_next_is_consumed) { + fmsg = msg_next; + } + + FSTR_P const msg_next_int = lcd_display_message_fullscreen(fmsg); + msg_next_is_consumed = strlen_P(FTOP(msg_next_int)) == 0; + if (!msg_next_is_consumed) msg_next = msg_next_int; + // Set the button response to MoreInfo so we keep coming back to this screen until all messages are consumed + SetButtonResponse(ButtonOperations::MoreInfo); + #else + // no lcd, no error display... just break the loop... + msg_next_is_consumed = false; + msg_next = nullptr; + SetButtonResponse(ButtonOperations::NoOperation); + #endif // HAS_WIRED_LCD + drawing_more_info_screen = false; + } + + /** + * @brief Renders any characters that are static on the MMU error screen i.e. they don't change. + * @param[in] ei Error code index + */ + static void ReportErrorHookStaticRender(uint8_t ei) { + #if HAS_WIRED_LCD + //! Show an error screen + //! When an MMU error occurs, the LCD content will look like this: + //! |01234567890123456789| + //! |MMU FW update needed| <- title/header of the error: max 20 characters + //! |prusa.io/04504 | <- URL max 20 characters + //! |FI:1 FS:1 5>3 t201°| <- status line, t is thermometer symbol + //! |>Retry >Done >W| <- buttons + bool two_choices = false; + + // Read and determine what operations should be shown on the menu + const uint8_t button_operation = PrusaErrorButtons(ei), + button_op_right = BUTTON_OP_RIGHT(button_operation), + button_op_middle = BUTTON_OP_MIDDLE(button_operation); + + // Check if the menu should have three or two choices + if (button_op_right == (uint8_t)ButtonOperations::NoOperation) { + // Two operations not specified, the error menu should only show two choices + two_choices = true; + } + + START_MENU(); + #ifndef __AVR__ + // TODO: I couldn't make this work on AVR + STATIC_ITEM_F(PrusaErrorTitle(ei), SS_DEFAULT | SS_INVERT); + + // Write the help page and error code + MString url(""); + url.appendf("prusa.io/04%hu", PrusaErrorCode(ei)); + STATIC_ITEM_F(nullptr, SS_DEFAULT, url.buffer()); + + //ReportErrorHookSensorLineRender(); + + editable.uint8 = button_op_middle; + ACTION_ITEM_F( + PrusaErrorButtonTitle(button_op_middle), + []{ SetButtonResponse((ButtonOperations)editable.uint8); } + ); + + if (!two_choices) { + editable.uint8 = button_op_right; + ACTION_ITEM_F( + PrusaErrorButtonTitle(button_op_right), + []{ SetButtonResponse((ButtonOperations)editable.uint8); } + ); + } + + // Add a More Info option + editable.uint8 = ei; + ACTION_ITEM_F( + GET_TEXT_F(MSG_BTN_MORE), + []{ + // only when the menu item is used push the current screen back + ui.push_current_screen(); + msg_next_is_consumed = false; + msg_next = nullptr; + SetButtonResponse(ButtonOperations::MoreInfo); + } + ); + + #endif // !__AVR__ + + // Render the choices + //if (two_choices) { + // lcd_show_choices_prompt_P( + // LCD_LEFT_BUTTON_CHOICE, + // PrusaErrorButtonTitle(button_op_middle), + // GET_TEXT(MSG_BTN_MORE), + // 18, nullptr + // ); + //} + //else { + // lcd_show_choices_prompt_P( + // LCD_MIDDLE_BUTTON_CHOICE, + // PrusaErrorButtonTitle(button_op_middle), + // PrusaErrorButtonTitle(button_op_right), + // 9, GET_TEXT(MSG_BTN_MORE) + // ); + //} + + END_MENU(); + //ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); + #endif // HAS_WIRED_LCD + } + + void ReportErrorHookSensorLineRender() { + #if HAS_WIRED_LCD + // Render static characters in third line + lcd_put_u8str( + 0, + LCD_HEIGHT - 1, + F("FI: FS: > " LCD_STR_THERMOMETER " " LCD_STR_DEGREE) + ); + #endif + } + + /** + * @brief Monitors the LCD button selection without blocking MMU communication + * @param[in] ei Error code index + * @return 0 if there is no knob click -- + * 1 if user clicked 'More' and firmware should render + * the error screen when ReportErrorHook is called next -- + * 2 if the user selects an operation and we would like + * to exit the error screen. The MMU will raise the menu + * again if the error is not solved. + */ + static uint8_t ReportErrorHookMonitor(uint8_t ei) { + uint8_t ret = 0; + if (GetButtonResponse() == ButtonOperations::MoreInfo) { + SetButtonResponse(ButtonOperations::NoOperation); + ret = 1; + } + else if (GetButtonResponse() != ButtonOperations::NoOperation) { + ret = 2; + } + // Next MMU error screen should reset the choice selection + // reset_button_selection = 1; + return ret; + } + + enum class ReportErrorHookStates : uint8_t { + RENDER_ERROR_SCREEN = 0, + MONITOR_SELECTION = 1, + DISMISS_ERROR_SCREEN = 2, + }; + + enum ReportErrorHookStates ReportErrorHookState = ReportErrorHookStates::RENDER_ERROR_SCREEN; + + // Helper variable to monitor knob in MMU error screen in blocking functions e.g. manage_response + static bool is_mmu_error_monitor_active; + + // Helper variable to stop rendering the error screen when the firmware is rendering complementary + // UI to resolve the error screen, for example tuning Idler Stallguard Threshold + // Set to false to allow the error screen to render again. + static bool putErrorScreenToSleep; + + void CheckErrorScreenUserInput() { + if (is_mmu_error_monitor_active) { + // Call this every iteration to keep the knob rotation responsive + // This includes when mmu_loop is called within manage_response + ReportErrorHook((CommandInProgress)mmu3.getCommandInProgress(), mmu3.getLastErrorCode(), mmu3.mmuLastErrorSource()); + } + } + + bool TuneMenuEntered() { + return putErrorScreenToSleep; + } + + void ReportErrorHook(CommandInProgress /*cip*/, ErrorCode ec, uint8_t /*es*/) { + if (putErrorScreenToSleep) return; + + if (mmu3.mmuCurrentErrorCode() == ErrorCode::OK && mmu3.mmuLastErrorSource() == MMU3::ErrorSourceMMU) { + // If the error code suddenly changes to OK, that means + // a button was pushed on the MMU and the LCD should + // dismiss the error screen until MMU raises a new error + ReportErrorHookState = ReportErrorHookStates::DISMISS_ERROR_SCREEN; + drawing_more_info_screen = false; + msg_next_is_consumed = true; + } + + const uint8_t ei = PrusaErrorCodeIndex((ErrorCode)ec); + + // This should be the equivalent of the switch..case above... + if ((uint8_t)ReportErrorHookState == (uint8_t)ReportErrorHookStates::RENDER_ERROR_SCREEN) { + KEEPALIVE_STATE(PAUSED_FOR_USER); + #if HAS_WIRED_LCD + drawing_more_info_screen = false; + msg_next_is_consumed = false; + msg_next = nullptr; + editable.uint8 = ei; + ui.defer_status_screen(); + ui.goto_screen([]{ ReportErrorHookStaticRender(editable.uint8); }); + #endif + ReportErrorHookState = ReportErrorHookStates::MONITOR_SELECTION; + } + + if ((uint8_t)ReportErrorHookState == (uint8_t)ReportErrorHookStates::MONITOR_SELECTION) { + is_mmu_error_monitor_active = true; + // ReportErrorHookDynamicRender(); // Render dynamic characters + sound_wait_for_user(); + uint8_t result = ReportErrorHookMonitor(ei); + if (result == 0) { + // No choice selected, return to loop() + } + else if (result == 1) { + // More Info button selected, change state + editable.uint8 = ei; + //ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); + ui.goto_screen(show_more_info_screen); + ReportErrorHookState = ReportErrorHookStates::MONITOR_SELECTION; + } + else if (result == 2) { + // Exit error screen and enable lcd updates + TERN_(HAS_WIRED_LCD, ui.return_to_status()); + sound_wait_for_user_reset(); + // Reset the state in case a new error is reported + is_mmu_error_monitor_active = false; + KEEPALIVE_STATE(IN_HANDLER); + ReportErrorHookState = ReportErrorHookStates::RENDER_ERROR_SCREEN; + } + return; // Always return to loop() to let MMU trigger a call to ReportErrorHook again + } + else if ((uint8_t)ReportErrorHookState == (uint8_t)ReportErrorHookStates::DISMISS_ERROR_SCREEN) { + TERN_(HAS_WIRED_LCD, ui.return_to_status()); + sound_wait_for_user_reset(); + // Reset the state in case a new error is reported + is_mmu_error_monitor_active = false; + KEEPALIVE_STATE(IN_HANDLER); + ReportErrorHookState = ReportErrorHookStates::RENDER_ERROR_SCREEN; + } + } + + void ReportProgressHook(CommandInProgress cip, ProgressCode ec) { + if (cip != CommandInProgress::NoCommand) { + // custom_message_type = CustomMsg::MMUProgress; + ui.set_status(ProgressCodeToText(ec)); + } + } + + TryLoadUnloadReporter::TryLoadUnloadReporter(float delta_mm) + : dpixel0(0), dpixel1(0), lcd_cursor_col(0) + , pixel_per_mm(0.5F * float(LCD_WIDTH) / (delta_mm) + ) { + //lcd_clearstatus(); + ui.reset_status(); + } + + TryLoadUnloadReporter::~TryLoadUnloadReporter() { + #if HAS_WIRED_LCD + // Delay the next status message just so + // the user can see the results clearly + ui.set_status_no_expire(ui.status_message); + #endif + } + + void TryLoadUnloadReporter::Render(uint8_t col, bool sensorState) { + #if HAS_WIRED_LCD + // Set the cursor position each time in case some other + // part of the firmware changes the cursor position + lcd_replace_status_char(col, sensorState ? LCD_STR_SOLID_BLOCK[0] : '-'); + if (ui.lcdDrawUpdate == LCDViewAction::LCDVIEW_NONE) + ui.draw_status_message(false); + #endif + } + + void TryLoadUnloadReporter::Progress(bool sensorState) { + // Always round up, you can only have 'whole' pixels. (floor is also an option) + dpixel1 = ceil((stepper_get_machine_position_E_mm() - planner_get_current_position_E()) * pixel_per_mm); + if (dpixel1 != dpixel0) { + dpixel0 = dpixel1; + if (lcd_cursor_col > (LCD_WIDTH - 1)) lcd_cursor_col = LCD_WIDTH - 1; + Render(lcd_cursor_col++, sensorState); + } + } + + void TryLoadUnloadReporter::DumpToSerial() { + char buf[LCD_WIDTH + 1]; + TERN_(HAS_WIRED_LCD, ui.status_message.copyto(buf)); + for (uint8_t i = 0; i < sizeof(buf); i++) { + // 0xFF is -1 when converting from unsigned to signed char + // If the number is negative, that means filament is present + buf[i] = (buf[i] < 0) ? '1' : '0'; + } + buf[LCD_WIDTH] = 0; + MMU2_ECHO_MSGLN(buf); + } + + void IncrementLoadFails() { + operation_statistics.increment_load_fails(); + } + + void IncrementMMUFails() { + operation_statistics.increment_mmu_fails(); + } + + bool cutter_enabled() { + return mmu3.cutter_mode > 0; + } + + void MakeSound(SoundType s) { + Sound_MakeSound((eSOUND_TYPE)s); + } + + static void fullScreenMsg(FSTR_P const fstr, uint8_t slot) { + #if HAS_WIRED_LCD + ui.clear_lcd(); + #ifndef __AVR__ + SETCURSOR(0, 1); + lcd_put_u8str(fstr); + lcd_put_lchar(' '); + lcd_put_int(slot + 1); + #else + UNUSED(fstr); + #endif + ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); + ui.screen_changed = true; + #endif + } + + void fullScreenMsgCut(uint8_t slot) { fullScreenMsg(GET_TEXT_F(MSG_CUT_FILAMENT), slot); } + void fullScreenMsgEject(uint8_t slot) { fullScreenMsg(GET_TEXT_F(MSG_EJECT_FROM_MMU), slot); } + void fullScreenMsgTest(uint8_t slot) { fullScreenMsg(GET_TEXT_F(MSG_TESTING_FILAMENT), slot); } + void fullScreenMsgLoad(uint8_t slot) { fullScreenMsg(GET_TEXT_F(MSG_LOADING_FILAMENT), slot); } + + void fullScreenMsgRestoringTemperature() { + #if HAS_WIRED_LCD + lcd_display_message_fullscreen(F("MMU Retry: Restoring temperature...")); + #endif + } + + void ScreenUpdateEnable() { + TERN_(HAS_WIRED_LCD, ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); + } + + void ScreenClear() { ui.clear_lcd(); } + + struct TuneItem { + uint8_t address; + uint8_t minValue; + uint8_t maxValue; + } + __attribute__((packed)); + + static const TuneItem TuneItems[] PROGMEM = { + { (uint8_t)Register::Selector_sg_thrs_R, 1, 4 }, + { (uint8_t)Register::Idler_sg_thrs_R, 2, 10 }, + }; + + static_assert(COUNT(TuneItems) == 2); + + typedef struct { + // Variables used when editing values. + const char* editLabel; + uint8_t editValueBits; // 8 or 16 + void* editValuePtr; + int16_t currentValue; + int16_t minEditValue; + int16_t maxEditValue; + int16_t minJumpValue; + } menu_data_edit_t; + + struct _menu_tune_data_t { + menu_data_edit_t reserved; // 13 bytes reserved for number editing functions + int8_t status; // 1 byte + uint8_t currentValue; // 1 byte + TuneItem item; // 3 bytes + }; + + //static_assert(sizeof(_menu_tune_data_t) == 18); + //static_assert(sizeof(menu_data)>= sizeof(_menu_tune_data_t), "_menu_tune_data_t doesn't fit into menu_data"); + + void tuneIdlerStallguardThresholdMenu() { + // const uint8_t menu_data[32] = "Set Stallguard Threshold"; + // //static constexpr _menu_tune_data_t * const _md = (_menu_tune_data_t*)&(menu_data[0]); + // static constexpr _menu_tune_data_t * const _md = (_menu_tune_data_t*)&(menu_data[0]); + + // // Do not timeout the screen, otherwise there will be FW crash (menu recursion) + // //lcd_timeoutToStatus.stop(); + //if (_md->status == 0) { + // _md->status = 1; // Menu entered for the first time + + // // Fetch the TuneItem from PROGMEM + // const uint8_t offset = (mmu3.mmuCurrentErrorCode() == ErrorCode::HOMING_IDLER_FAILED) ? 1 : 0; + // memcpy_P(&(_md->item), &TuneItems[offset], sizeof(TuneItem)); + + // // Fetch the value which is currently in MMU EEPROM + // mmu3.readRegister(_md->item.address); + // _md->currentValue = mmu3.getLastReadRegisterValue(); + //} + + // //MENU_BEGIN(); + // //ON_MENU_LEAVE( + // // mmu3.writeRegister(_md->item.address, (uint16_t)_md->currentValue); + // // putErrorScreenToSleep = false; + // // lcd_return_to_status(); + // // return; + // //); + // //MENU_ITEM_BACK(MSG_DONE); + // //MENU_ITEM_EDIT_int3_P( + // // _i("Sensitivity"), ////MSG_MMU_SENSITIVITY c=18 + // // &_md->currentValue, + // // _md->item.minValue, + // // _md->item.maxValue + // //); + // //MENU_END(); + + //START_MENU(); + //BACK_ITEM(MSG_BACK); + //EDIT_ITEM( + // int8, + // MSG_MMU_SENSITIVITY, + // &_md->currentValue, + // _md->item.minValue, + // _md->item.maxValue, + // []{ + // write_register_and_return_to_status_menu(_md->item.address, _md->currentValue); + // } + // ); + //END_MENU(); + } + + void write_register_and_return_to_status_menu(uint8_t address, uint8_t value) { + mmu3.writeRegister(address, (uint16_t)value); + putErrorScreenToSleep = false; + ui.return_to_status(); + } + + void tuneIdlerStallguardThreshold() { + putErrorScreenToSleep = true; + //menu_submenu(tuneIdlerStallguardThresholdMenu); + } + +} // MMU3 + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_reporting.h b/Marlin/src/feature/mmu3/mmu3_reporting.h new file mode 100644 index 0000000000..d3e8db9c5e --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_reporting.h @@ -0,0 +1,168 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_reporting.h + */ + +#include "../../MarlinCore.h" + +#include +#include "mmu_hw/error_codes.h" +#include "mmu_hw/progress_codes.h" + +namespace MMU3 { + + enum CommandInProgress : uint8_t { + NoCommand = 0, + CutFilament = 'K', + EjectFilament = 'E', + Homing = 'H', + LoadFilament = 'L', + Reset = 'X', + ToolChange = 'T', + UnloadFilament = 'U', + }; + + /** + * Data class for MMU operation statistics. + * + * This is used to load/save data from/to EEPROM. + * The data is initialized by the settings.load() method. + */ + class OperationStatistics { + public: + void increment_load_fails(); + void increment_mmu_fails(); + void increment_tool_change_counter(); + bool reset_per_print_stats(); // Reset only the per print stats. + bool reset_fail_stats(); // Reset only fail stats and keep tool change counters + bool reset_stats(); // Reset MMU stats and update EEPROM + + static uint16_t fail_total_num; // total failures + static uint8_t fail_num; // fails during print + static uint16_t load_fail_total_num; // total load failures + static uint8_t load_fail_num; // load failures during print + static uint16_t tool_change_counter; // number of tool changes during print + static uint32_t tool_change_total_counter; // number of total tool changes + static int fail_total_num_addr; // total failures EEPROM addr + static int fail_num_addr; // fails during print EEPROM addr + static int load_fail_total_num_addr; // total load failures EEPROM addr + static int load_fail_num_addr; // load failures during print EEPROM addr + static int tool_change_counter_addr; // number of tool changes EEPROM addr + static int tool_change_total_counter_addr; // number of total tool changes EEPROM addr + }; + + extern OperationStatistics operation_statistics; + + // Called at the begin of every MMU operation + void BeginReport(CommandInProgress cip, ProgressCode ec); + + // Called at the end of every MMU operation + void EndReport(CommandInProgress cip, ProgressCode ec); + + // Checks for error screen user input, if the error screen is open + void CheckErrorScreenUserInput(); + + // Return true if the error screen is sleeping in the background + // Error screen sleeps when the firmware is rendering complementary + // UI to resolve the error screen, for example tuning Idler Stallguard Threshold + bool TuneMenuEntered(); + + // @brief Called when the MMU or MK3S sends operation error (even repeatedly). + // Render MMU error screen on the LCD. This must be non-blocking + // and allow the MMU and printer to communicate with each other. + // @param[in] ec error code + // @param[in] es error source + void ReportErrorHook(CommandInProgress cip, ErrorCode ec, uint8_t es); + + // Called when the MMU sends operation progress update + void ReportProgressHook(CommandInProgress cip, ProgressCode ec); + + struct TryLoadUnloadReporter { + TryLoadUnloadReporter(float delta_mm); + ~TryLoadUnloadReporter(); + void Progress(bool sensorState); + void DumpToSerial(); + + private: + // @brief Add one block to the progress bar + // @param col pixel position on the LCD status line, should range from 0 to (LCD_WIDTH - 1) + // @param sensorState if true, filament is not present, else filament is present. This controls which character to render + void Render(uint8_t col, bool sensorState); + + uint8_t dpixel0, dpixel1; + uint8_t lcd_cursor_col; + // The total length is twice delta_mm. Divide that length by number of pixels + // available to get length per pixel. + // Note: Below is the reciprocal of (2 * delta_mm) / LCD_WIDTH [mm/pixel] + float pixel_per_mm; + }; + + // Remders the sensor status line. Also used by the "resume temperature" screen. + void ReportErrorHookDynamicRender(); + + // Renders the static part of the sensor state line. Also used by "resuming temperature screen" + void ReportErrorHookSensorLineRender(); + + // @return true if the MMU is communicating and available. Can change at runtime. + //bool MMUAvailable(); + + // Global Enable/Disable use MMU (to be stored in EEPROM) + //bool UseMMU(); + + // Disable MMU in EEPROM + //void DisableMMUInSettings(); + + // Increments EEPROM cell - number of failed loads into the nozzle + // Note: technically, this is not an MMU error but an error of the printer. + void IncrementLoadFails(); + + // Increments EEPROM cell - number of MMU errors + void IncrementMMUFails(); + + // @return true when Cutter is enabled in the menus + bool cutter_enabled(); + + // Beware: enum values intentionally chosen to match the 8bit FW to save code size + enum SoundType { + Prompt = 2, + Confirm = 3 + }; + + void MakeSound(SoundType s); + + void fullScreenMsgCut(uint8_t slot); + void fullScreenMsgEject(uint8_t slot); + void fullScreenMsgTest(uint8_t slot); + void fullScreenMsgLoad(uint8_t slot); + void fullScreenMsgRestoringTemperature(); + + void ScreenUpdateEnable(); + void ScreenClear(); + + void tuneIdlerStallguardThreshold(); + + void write_register_and_return_to_status_menu(uint8_t address, uint8_t value); + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_state.h b/Marlin/src/feature/mmu3/mmu3_state.h new file mode 100644 index 0000000000..036d3ae255 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_state.h @@ -0,0 +1,48 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_state.h + */ + +#include + +namespace MMU3 { + /** + * @brief status of mmu + * + * States of a printer with the MMU: + * - Active + * - Connecting + * - Stopped + * + * When the printer's FW starts, the MMU mode is either Stopped or NotResponding (based on user's preference). + * When the MMU successfully establishes communication, the state changes to Active. + */ + enum class xState : uint_fast8_t { + Active, //!< MMU has been detected, connected, communicates and is ready to be worked with. + Connecting, //!< MMU is connected but it doesn't communicate (yet). The user wants the MMU, but it is not ready to be worked with. + Stopped //!< The user doesn't want the printer to work with the MMU. The MMU itself is not powered and does not work at all. + }; + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/mmu3_supported_version.h b/Marlin/src/feature/mmu3/mmu3_supported_version.h new file mode 100644 index 0000000000..fe21c79d5a --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu3_supported_version.h @@ -0,0 +1,32 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * mmu2_supported_version.h + */ + +#include + +#define mmuVersionMajor 3 +#define mmuVersionMinor 0 +#define mmuVersionPatch 2 diff --git a/Marlin/src/feature/mmu3/mmu_hw/buttons.h b/Marlin/src/feature/mmu3/mmu_hw/buttons.h new file mode 100644 index 0000000000..2b35d6339c --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu_hw/buttons.h @@ -0,0 +1,73 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * buttons.h + */ + +#include + +// Helper macros to parse the operations from Btns() +#define BUTTON_OP_RIGHT(X) ((X & 0xF0) >> 4) +#define BUTTON_OP_MIDDLE(X) (X & 0x0F) + +namespace MMU3 { + +// Will be mapped onto dialog button responses in the FW +// Those responses have their unique+translated texts as well +enum class ButtonOperations : uint8_t { + NoOperation = 0, + Retry = 1, + Continue = 2, + ResetMMU = 3, + Unload = 4, + Load = 5, + Eject = 6, + Tune = 7, + StopPrint = 8, + DisableMMU = 9, + MoreInfo = 10, +}; + +// Button codes + extended actions performed on the printer's side +enum class Buttons : uint_least8_t { + Right = 0, + Middle, + Left, + + // Performed on the printer's side + ResetMMU, + Load, + Eject, + StopPrint, + DisableMMU, + TuneMMU, // Printer changes MMU register value + + NoButton = 0xFF // should be kept last +}; + +constexpr uint_least8_t buttons_to_uint8t(Buttons b) { + return static_cast(b); +} + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/mmu_hw/check-pce.sh b/Marlin/src/feature/mmu3/mmu_hw/check-pce.sh new file mode 100755 index 0000000000..197bc6dcc5 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu_hw/check-pce.sh @@ -0,0 +1,55 @@ +#!/bin/bash + +# download Prusa Error Codes for MMU +#wget https://raw.githubusercontent.com/3d-gussner/Prusa-Error-Codes/master/04_MMU/error-codes.yaml --output-document=error-codes.yaml +wget https://raw.githubusercontent.com/prusa3d/Prusa-Error-Codes/master/04_MMU/error-codes.yaml --output-document=error-codes.yaml + +oifs="$IFS" ## save original IFS +IFS=$'\n' ## set IFS to break on newline +codes=($(cat error-codes.yaml |grep "code:" |cut -d '"' -f2)) +titles=($(cat error-codes.yaml |grep 'title:' |cut -d '"' -f2)) +texts=($(cat error-codes.yaml |grep "text:" |cut -d '"' -f2)) +actions=($(cat error-codes.yaml |grep "action:" |cut -d ':' -f2)) +ids=($(cat error-codes.yaml |grep "id:" |cut -d '"' -f2)) +IFS="$oifs" ## restore original IFS + +filename=errors_list.h + +clear +for ((i = 0; i < ${#codes[@]}; i++)) do + code=${codes[i]} + id=$(cat $filename |grep "${code#04*}" | cut -d "=" -f1 | cut -d "_" -f3- |cut -d " " -f1) + title=$(cat $filename |grep "${id}" |grep --max-count=1 "MSG_TITLE" |cut -d '"' -f2) + text=$(cat $filename |grep "${id}" |grep --max-count=1 "MSG_DESC" |cut -d '"' -f2) + action1=$(cat $filename |grep "),//$id"| cut -d "," -f1) + action2=$(cat $filename |grep "),//$id"| cut -d "," -f2) + action1=$(echo $action1 | cut -d ":" -f2- |cut -d ":" -f2) + action2=$(echo $action2 | cut -d ":" -f2- |cut -d ":" -f2 |cut -d ")" -f1) + if [ "$action2" == "NoOperation" ]; then + action=" [$action1]" + else + action=" [$action1,$action2]" + fi + echo -n "code: $code |" + if [ "$id" != "${ids[i]}" ]; then + echo -n "$(tput setaf 1) $id $(tput sgr0) # $(tput setaf 2)${ids[i]}$(tput sgr0)|" + else + echo -n " $id |" + fi + if [ "$title" != "${titles[i]}" ]; then + echo -n "$(tput setaf 1) $title $(tput sgr0) # $(tput setaf 2)${titles[i]}$(tput sgr0)|" + else + echo -n " $title |" + fi + if [ "$text" != "${texts[i]}" ]; then + echo -n "$(tput setaf 1) $text $(tput sgr0) # $(tput setaf 2)${texts[i]}$(tput sgr0)|" + else + echo -n " $text |" + fi + if [ "$action" != "${actions[i]}" ]; then + echo -n "$(tput setaf 1) $action $(tput sgr0) # $(tput setaf 2)${actions[i]}$(tput sgr0)|" + else + echo -n " $action |" + fi + echo +done diff --git a/Marlin/src/feature/mmu3/mmu_hw/error_codes.h b/Marlin/src/feature/mmu3/mmu_hw/error_codes.h new file mode 100644 index 0000000000..b0bc36e206 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu_hw/error_codes.h @@ -0,0 +1,151 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * error_codes.h + */ + +#include + +/** + * A complete set of error codes which may be a result of a high-level command/operation. + * This header file should be included in the printer's firmware as well as a reference, + * therefore the error codes have been extracted to one place. + * + * Please note the errors are intentionally coded as "negative" values (highest bit set), + * because they are a complement to reporting the state of the high-level state machines - + * positive values are considered as normal progress, negative values are errors. + * + * Please note, that multiple TMC errors can occur at once, thus they are defined as a bitmask of the higher byte. + * Also, as there are 3 TMC drivers on the board, each error is added a bit for the corresponding TMC - + * TMC_PULLEY_BIT, TMC_SELECTOR_BIT, TMC_IDLER_BIT, + * The resulting error is a bitwise OR over 3 TMC drivers and their status, which should cover most of the situations correctly. + */ +enum class ErrorCode : uint_fast16_t { + RUNNING = 0x0000, //!< the operation is still running - keep this value as ZERO as it is used for initialization of error codes as well + OK = 0x0001, //!< the operation finished OK + + // TMC bit masks + TMC_PULLEY_BIT = 0x0040, //!< +64 TMC Pulley bit + TMC_SELECTOR_BIT = 0x0080, //!< +128 TMC Pulley bit + TMC_IDLER_BIT = 0x0100, //!< +256 TMC Pulley bit + + // Unload Filament related error codes + FINDA_DIDNT_SWITCH_ON = 0x8001, //!< E32769 FINDA didn't switch on while loading filament - either there is something blocking the metal ball or a cable is broken/disconnected + FINDA_DIDNT_SWITCH_OFF = 0x8002, //!< E32770 FINDA didn't switch off while unloading filament + + FSENSOR_DIDNT_SWITCH_ON = 0x8003, //!< E32771 Filament sensor didn't switch on while performing LoadFilament + FSENSOR_DIDNT_SWITCH_OFF = 0x8004, //!< E32772 Filament sensor didn't switch off while performing UnloadFilament + + FILAMENT_ALREADY_LOADED = 0x8005, //!< E32773 cannot perform operation LoadFilament or move the selector as the filament is already loaded + + INVALID_TOOL = 0x8006, //!< E32774 tool/slot index out of range (typically issuing T5 into an MMU with just 5 slots - valid range 0-4) + + HOMING_FAILED = 0x8007, //!< generic homing failed error - always reported with the corresponding axis bit set (Idler or Selector) as follows: + HOMING_SELECTOR_FAILED = HOMING_FAILED | TMC_SELECTOR_BIT, //!< E32903 the Selector was unable to home properly - that means something is blocking its movement + HOMING_IDLER_FAILED = HOMING_FAILED | TMC_IDLER_BIT, //!< E33031 the Idler was unable to home properly - that means something is blocking its movement + STALLED_PULLEY = HOMING_FAILED | TMC_PULLEY_BIT, //!< E32839 for the Pulley "homing" means just StallGuard detected during Pulley's operation (Pulley doesn't home) + + FINDA_VS_EEPROM_DISREPANCY = 0x8008, //!< E32776 FINDA is pressed but we have no such record in EEPROM - this can only happen at the start of the MMU and can be resolved by issuing an Unload command + + FSENSOR_TOO_EARLY = 0x8009, //!< E32777 FSensor triggered while doing FastFeedToBondtech - that means either: + //!< - the PTFE is too short + //!< - a piece of filament was left inside - pushed in front of the loaded filament causing the fsensor trigger too early + //!< - fsensor is faulty producing bogus triggers + + FINDA_FLICKERS = 0x800A, //!< FINDA flickers - seems to be badly calibrated and happens to be pressed at spots where it used to be not pressed before. + //!< The user is obliged to inspect FINDA and tune its switching + + MOVE_FAILED = 0x800B, //!< generic move failed error - always reported with the corresponding axis bit set (Idler or Selector) as follows: + MOVE_SELECTOR_FAILED = MOVE_FAILED | TMC_SELECTOR_BIT, //!< E32905 the Selector was unable to move to desired position properly - that means something is blocking its movement, e.g. a piece of filament got out of pulley body + MOVE_IDLER_FAILED = MOVE_FAILED | TMC_IDLER_BIT, //!< E33033 the Idler was unable to move - unused at the time of creation, but added for completeness + MOVE_PULLEY_FAILED = MOVE_FAILED | TMC_PULLEY_BIT, //!< E32841 the Pulley was unable to move - unused at the time of creation, but added for completeness + + FILAMENT_EJECTED = 0x800C, //!< Filament was ejected, waiting for user input - technically, this is not an error + + MCU_UNDERVOLTAGE_VCC = 0x800D, //!< MCU VCC rail undervoltage. + + FILAMENT_CHANGE = 0x8029, //!< E32809 internal error of the printer - try-load-unload sequence detected missing filament -> failed load into the nozzle + LOAD_TO_EXTRUDER_FAILED = 0x802A, //!< E32810 internal error of the printer - try-load-unload sequence detected missing filament -> failed load into the nozzle + QUEUE_FULL = 0x802B, //!< E32811 internal logic error - attempt to move with a full queue + VERSION_MISMATCH = 0x802C, //!< E32812 internal error of the printer - incompatible version of the MMU FW + PROTOCOL_ERROR = 0x802D, //!< E32813 internal error of the printer - communication with the MMU got garbled - protocol decoder couldn't decode the incoming messages + MMU_NOT_RESPONDING = 0x802E, //!< E32814 internal error of the printer - communication with the MMU is not working + INTERNAL = 0x802F, //!< E32815 internal runtime error (software) + + // TMC driver init error - TMC dead or bad communication + // - E33344 Pulley TMC driver + // - E33408 Selector TMC driver + // - E33536 Idler TMC driver + // - E33728 All 3 TMC driver + TMC_IOIN_MISMATCH = 0x8200, + + // TMC driver reset - recoverable, we just need to rehome the axis + // Idler: can be rehomed any time + // Selector: if there is a filament, remove it and rehome, if there is no filament, just rehome + // Pulley: do nothing - for the loading sequence - just restart and move slowly, for the unload sequence just restart + // - E33856 Pulley TMC driver + // - E33920 Selector TMC driver + // - E34048 Idler TMC driver + // - E34240 All 3 TMC driver + TMC_RESET = 0x8400, + + // not enough current for the TMC, NOT RECOVERABLE + // - E34880 Pulley TMC driver + // - E34944 Selector TMC driver + // - E35072 Idler TMC driver + // - E35264 All 3 TMC driver + TMC_UNDERVOLTAGE_ON_CHARGE_PUMP = 0x8800, + + // TMC driver serious error - short to ground on coil A or coil B - dangerous to recover + // - E36928 Pulley TMC driver + // - E36992 Selector TMC driver + // - E37120 Idler TMC driver + // - E37312 All 3 TMC driver + TMC_SHORT_TO_GROUND = 0x9000, + + // TMC driver over temperature warning - can be recovered by restarting the driver. + // If this error happens, we should probably go into the error state as soon as the current command is finished. + // The driver technically still works at this point. + // - E41024 Pulley TMC driver + // - E41088 Selector TMC driver + // - E41216 Idler TMC driver + // - E41408 All 3 TMC driver + TMC_OVER_TEMPERATURE_WARN = 0xA000, + + // TMC driver over temperature error - we really shouldn't ever reach this error. + // It can still be recovered if the driver cools down below 120C. + // The driver needs to be disabled and enabled again for operation to resume after this error is cleared. + // - E49216 Pulley TMC driver + // - E49280 Selector TMC driver + // - E49408 Idler TMC driver + // - E49600 All 3 TMC driver + TMC_OVER_TEMPERATURE_ERROR = 0xC000, + + // TMC driver - IO pins are unreliable. While in theory it's recoverable, in practice it most likely + // means your hardware is borked (we can't command the drivers reliably via STEP/EN/DIR due to electrical + // issues or hardware fault. Possible "fixable" cause is undervoltage on the 5v logic line. + // Unfixable possible cause: bad or cracked solder joints on the PCB, failed shift register, failed driver. + MMU_SOLDERING_NEEDS_ATTENTION = 0xC200, + +}; diff --git a/Marlin/src/feature/mmu3/mmu_hw/errors_list.h b/Marlin/src/feature/mmu3/mmu_hw/errors_list.h new file mode 100644 index 0000000000..9cfdba2283 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu_hw/errors_list.h @@ -0,0 +1,351 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * errors_list.h + */ + +/** + * Extracted from Prusa-Error-Codes repo + * Subject to automation and optimization + * BEWARE - This file should only be included by mmu2_error_converter.cpp! + */ +#include "inttypes.h" +#include "../../../core/language.h" +#include "../../../lcd/marlinui.h" +#ifdef __AVR__ + #include +#endif +#include "buttons.h" +#include "../ultralcd.h" + +namespace MMU3 { + +static constexpr uint8_t ERR_MMU_CODE = 4; + +typedef enum : uint16_t { + ERR_UNDEF = 0, + + ERR_MECHANICAL = 100, + ERR_MECHANICAL_FINDA_DIDNT_TRIGGER = 101, + ERR_MECHANICAL_FINDA_FILAMENT_STUCK = 102, + ERR_MECHANICAL_FSENSOR_DIDNT_TRIGGER = 103, + ERR_MECHANICAL_FSENSOR_FILAMENT_STUCK = 104, + + ERR_MECHANICAL_PULLEY_CANNOT_MOVE = 105, + ERR_MECHANICAL_FSENSOR_TOO_EARLY = 106, + ERR_MECHANICAL_INSPECT_FINDA = 107, + ERR_MECHANICAL_LOAD_TO_EXTRUDER_FAILED = 108, + ERR_MECHANICAL_SELECTOR_CANNOT_HOME = 115, + ERR_MECHANICAL_SELECTOR_CANNOT_MOVE = 116, + ERR_MECHANICAL_IDLER_CANNOT_HOME = 125, + ERR_MECHANICAL_IDLER_CANNOT_MOVE = 126, + + ERR_TEMPERATURE = 200, + ERR_TEMPERATURE_WARNING_TMC_PULLEY_TOO_HOT = 201, + ERR_TEMPERATURE_WARNING_TMC_SELECTOR_TOO_HOT = 211, + ERR_TEMPERATURE_WARNING_TMC_IDLER_TOO_HOT = 221, + + ERR_TEMPERATURE_TMC_PULLEY_OVERHEAT_ERROR = 202, + ERR_TEMPERATURE_TMC_SELECTOR_OVERHEAT_ERROR = 212, + ERR_TEMPERATURE_TMC_IDLER_OVERHEAT_ERROR = 222, + + + ERR_ELECTRICAL = 300, + ERR_ELECTRICAL_TMC_PULLEY_DRIVER_ERROR = 301, + ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_ERROR = 311, + ERR_ELECTRICAL_TMC_IDLER_DRIVER_ERROR = 321, + + ERR_ELECTRICAL_TMC_PULLEY_DRIVER_RESET = 302, + ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_RESET = 312, + ERR_ELECTRICAL_TMC_IDLER_DRIVER_RESET = 322, + + ERR_ELECTRICAL_TMC_PULLEY_UNDERVOLTAGE_ERROR = 303, + ERR_ELECTRICAL_TMC_SELECTOR_UNDERVOLTAGE_ERROR = 313, + ERR_ELECTRICAL_TMC_IDLER_UNDERVOLTAGE_ERROR = 323, + + ERR_ELECTRICAL_TMC_PULLEY_DRIVER_SHORTED = 304, + ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_SHORTED = 314, + ERR_ELECTRICAL_TMC_IDLER_DRIVER_SHORTED = 324, + + ERR_ELECTRICAL_MMU_PULLEY_SELFTEST_FAILED = 305, + ERR_ELECTRICAL_MMU_SELECTOR_SELFTEST_FAILED = 315, + ERR_ELECTRICAL_MMU_IDLER_SELFTEST_FAILED = 325, + + ERR_ELECTRICAL_MMU_MCU_ERROR = 306, + + ERR_CONNECT = 400, + ERR_CONNECT_MMU_NOT_RESPONDING = 401, + ERR_CONNECT_COMMUNICATION_ERROR = 402, + + + ERR_SYSTEM = 500, + ERR_SYSTEM_FILAMENT_ALREADY_LOADED = 501, + ERR_SYSTEM_INVALID_TOOL = 502, + ERR_SYSTEM_QUEUE_FULL = 503, + ERR_SYSTEM_FW_UPDATE_NEEDED = 504, + ERR_SYSTEM_FW_RUNTIME_ERROR = 505, + ERR_SYSTEM_UNLOAD_MANUALLY = 506, + ERR_SYSTEM_FILAMENT_EJECTED = 507, + ERR_SYSTEM_FILAMENT_CHANGE = 508, + + ERR_OTHER_UNKNOWN_ERROR = 900 +} err_num_t; + +// Avr gcc has serious trouble understanding static data structures in PROGMEM +// and inadvertently falls back to copying the whole structure into RAM (which is obviously unwanted). +// But since this file ought to be generated in the future from yaml prescription, +// it really makes no difference if there are "nice" data structures or plain arrays. +static const constexpr err_num_t errorCodes[] PROGMEM = { + ERR_MECHANICAL_FINDA_DIDNT_TRIGGER, + ERR_MECHANICAL_FINDA_FILAMENT_STUCK, + ERR_MECHANICAL_FSENSOR_DIDNT_TRIGGER, + ERR_MECHANICAL_FSENSOR_FILAMENT_STUCK, + ERR_MECHANICAL_PULLEY_CANNOT_MOVE, + ERR_MECHANICAL_FSENSOR_TOO_EARLY, + ERR_MECHANICAL_INSPECT_FINDA, + ERR_MECHANICAL_LOAD_TO_EXTRUDER_FAILED, + ERR_MECHANICAL_SELECTOR_CANNOT_HOME, + ERR_MECHANICAL_SELECTOR_CANNOT_MOVE, + ERR_MECHANICAL_IDLER_CANNOT_HOME, + ERR_MECHANICAL_IDLER_CANNOT_MOVE, + ERR_TEMPERATURE_WARNING_TMC_PULLEY_TOO_HOT, + ERR_TEMPERATURE_WARNING_TMC_SELECTOR_TOO_HOT, + ERR_TEMPERATURE_WARNING_TMC_IDLER_TOO_HOT, + ERR_TEMPERATURE_TMC_PULLEY_OVERHEAT_ERROR, + ERR_TEMPERATURE_TMC_SELECTOR_OVERHEAT_ERROR, + ERR_TEMPERATURE_TMC_IDLER_OVERHEAT_ERROR, + ERR_ELECTRICAL_TMC_PULLEY_DRIVER_ERROR, + ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_ERROR, + ERR_ELECTRICAL_TMC_IDLER_DRIVER_ERROR, + ERR_ELECTRICAL_TMC_PULLEY_DRIVER_RESET, + ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_RESET, + ERR_ELECTRICAL_TMC_IDLER_DRIVER_RESET, + ERR_ELECTRICAL_TMC_PULLEY_UNDERVOLTAGE_ERROR, + ERR_ELECTRICAL_TMC_SELECTOR_UNDERVOLTAGE_ERROR, + ERR_ELECTRICAL_TMC_IDLER_UNDERVOLTAGE_ERROR, + ERR_ELECTRICAL_TMC_PULLEY_DRIVER_SHORTED, + ERR_ELECTRICAL_TMC_SELECTOR_DRIVER_SHORTED, + ERR_ELECTRICAL_TMC_IDLER_DRIVER_SHORTED, + ERR_ELECTRICAL_MMU_PULLEY_SELFTEST_FAILED, + ERR_ELECTRICAL_MMU_SELECTOR_SELFTEST_FAILED, + ERR_ELECTRICAL_MMU_IDLER_SELFTEST_FAILED, + ERR_ELECTRICAL_MMU_MCU_ERROR, + ERR_CONNECT_MMU_NOT_RESPONDING, + ERR_CONNECT_COMMUNICATION_ERROR, + ERR_SYSTEM_FILAMENT_ALREADY_LOADED, + ERR_SYSTEM_INVALID_TOOL, + ERR_SYSTEM_QUEUE_FULL, + ERR_SYSTEM_FW_UPDATE_NEEDED, + ERR_SYSTEM_FW_RUNTIME_ERROR, + ERR_SYSTEM_UNLOAD_MANUALLY, + ERR_SYSTEM_FILAMENT_EJECTED, + ERR_SYSTEM_FILAMENT_CHANGE, + ERR_OTHER_UNKNOWN_ERROR +}; + +FSTR_P const errorTitles[] PROGMEM = { + GET_TEXT_F(MSG_TITLE_FINDA_DIDNT_TRIGGER), + GET_TEXT_F(MSG_TITLE_FINDA_FILAMENT_STUCK), + GET_TEXT_F(MSG_TITLE_FSENSOR_DIDNT_TRIGGER), + GET_TEXT_F(MSG_TITLE_FSENSOR_FILAMENT_STUCK), + GET_TEXT_F(MSG_TITLE_PULLEY_CANNOT_MOVE), + GET_TEXT_F(MSG_TITLE_FSENSOR_TOO_EARLY), + GET_TEXT_F(MSG_TITLE_INSPECT_FINDA), + GET_TEXT_F(MSG_TITLE_LOAD_TO_EXTRUDER_FAILED), + GET_TEXT_F(MSG_TITLE_SELECTOR_CANNOT_HOME), + GET_TEXT_F(MSG_TITLE_SELECTOR_CANNOT_MOVE), + GET_TEXT_F(MSG_TITLE_IDLER_CANNOT_HOME), + GET_TEXT_F(MSG_TITLE_IDLER_CANNOT_MOVE), + GET_TEXT_F(MSG_TITLE_TMC_WARNING_TMC_TOO_HOT), + GET_TEXT_F(MSG_TITLE_TMC_WARNING_TMC_TOO_HOT), + GET_TEXT_F(MSG_TITLE_TMC_WARNING_TMC_TOO_HOT), + GET_TEXT_F(MSG_TITLE_TMC_OVERHEAT_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_OVERHEAT_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_OVERHEAT_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_RESET), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_RESET), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_RESET), + GET_TEXT_F(MSG_TITLE_TMC_UNDERVOLTAGE_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_UNDERVOLTAGE_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_UNDERVOLTAGE_ERROR), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_SHORTED), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_SHORTED), + GET_TEXT_F(MSG_TITLE_TMC_DRIVER_SHORTED), + GET_TEXT_F(MSG_TITLE_SELFTEST_FAILED), + GET_TEXT_F(MSG_TITLE_SELFTEST_FAILED), + GET_TEXT_F(MSG_TITLE_SELFTEST_FAILED), + GET_TEXT_F(MSG_TITLE_MMU_MCU_ERROR), + GET_TEXT_F(MSG_TITLE_MMU_NOT_RESPONDING), + GET_TEXT_F(MSG_TITLE_COMMUNICATION_ERROR), + GET_TEXT_F(MSG_TITLE_FILAMENT_ALREADY_LOADED), + GET_TEXT_F(MSG_TITLE_INVALID_TOOL), + GET_TEXT_F(MSG_TITLE_QUEUE_FULL), + GET_TEXT_F(MSG_TITLE_FW_UPDATE_NEEDED), + GET_TEXT_F(MSG_TITLE_FW_RUNTIME_ERROR), + GET_TEXT_F(MSG_TITLE_UNLOAD_MANUALLY), + GET_TEXT_F(MSG_TITLE_FILAMENT_EJECTED), + GET_TEXT_F(MSG_TITLE_FILAMENT_CHANGE), + GET_TEXT_F(MSG_TITLE_UNKNOWN_ERROR) +}; + +// @@TODO Looking at the texts, they can be composed of several parts and/or parameterized (could save a lot of space) ) +// Moreover, some of them have been disabled in favour of saving some more code size. + +FSTR_P const errorDescs[] PROGMEM = { + GET_TEXT_F(MSG_DESC_FINDA_DIDNT_TRIGGER), + GET_TEXT_F(MSG_DESC_FINDA_FILAMENT_STUCK), + GET_TEXT_F(MSG_DESC_FSENSOR_DIDNT_TRIGGER), + GET_TEXT_F(MSG_DESC_FSENSOR_FILAMENT_STUCK), + GET_TEXT_F(MSG_DESC_PULLEY_CANNOT_MOVE), + GET_TEXT_F(MSG_DESC_FSENSOR_TOO_EARLY), + GET_TEXT_F(MSG_DESC_INSPECT_FINDA), + GET_TEXT_F(MSG_DESC_LOAD_TO_EXTRUDER_FAILED), + GET_TEXT_F(MSG_DESC_SELECTOR_CANNOT_HOME), + GET_TEXT_F(MSG_DESC_CANNOT_MOVE), + GET_TEXT_F(MSG_DESC_IDLER_CANNOT_HOME), + GET_TEXT_F(MSG_DESC_CANNOT_MOVE), + GET_TEXT_F(MSG_DESC_TMC), // WARNING_TMC_PULLEY_TOO_HOT + GET_TEXT_F(MSG_DESC_TMC), // WARNING_TMC_SELECTOR_TOO_HOT + GET_TEXT_F(MSG_DESC_TMC), // WARNING_TMC_IDLER_TOO_HOT + GET_TEXT_F(MSG_DESC_TMC), // TMC_PULLEY_OVERHEAT_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_SELECTOR_OVERHEAT_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_IDLER_OVERHEAT_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_PULLEY_DRIVER_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_SELECTOR_DRIVER_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_IDLER_DRIVER_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_PULLEY_DRIVER_RESET + GET_TEXT_F(MSG_DESC_TMC), // TMC_SELECTOR_DRIVER_RESET + GET_TEXT_F(MSG_DESC_TMC), // TMC_IDLER_DRIVER_RESET + GET_TEXT_F(MSG_DESC_TMC), // TMC_PULLEY_UNDERVOLTAGE_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_SELECTOR_UNDERVOLTAGE_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_IDLER_UNDERVOLTAGE_ERROR + GET_TEXT_F(MSG_DESC_TMC), // TMC_PULLEY_DRIVER_SHORTED + GET_TEXT_F(MSG_DESC_TMC), // TMC_SELECTOR_DRIVER_SHORTED + GET_TEXT_F(MSG_DESC_TMC), // TMC_IDLER_DRIVER_SHORTED + GET_TEXT_F(MSG_DESC_TMC), // MMU_PULLEY_SELFTEST_FAILED + GET_TEXT_F(MSG_DESC_TMC), // MMU_SELECTOR_SELFTEST_FAILED + GET_TEXT_F(MSG_DESC_TMC), // MMU_IDLER_SELFTEST_FAILED + GET_TEXT_F(MSG_DESC_TMC), // MSG_DESC_MMU_MCU_ERROR + GET_TEXT_F(MSG_DESC_MMU_NOT_RESPONDING), + GET_TEXT_F(MSG_DESC_COMMUNICATION_ERROR), + GET_TEXT_F(MSG_DESC_FILAMENT_ALREADY_LOADED), + GET_TEXT_F(MSG_DESC_INVALID_TOOL), + GET_TEXT_F(MSG_DESC_QUEUE_FULL), + GET_TEXT_F(MSG_DESC_FW_UPDATE_NEEDED), + GET_TEXT_F(MSG_DESC_FW_RUNTIME_ERROR), + GET_TEXT_F(MSG_DESC_UNLOAD_MANUALLY), + GET_TEXT_F(MSG_DESC_FILAMENT_EJECTED), + GET_TEXT_F(MSG_DESC_FILAMENT_CHANGE), + GET_TEXT_F(MSG_DESC_UNKNOWN_ERROR) +}; + +// We have max 3 buttons/operations to select from. +// One of them is "More" to show the explanation text normally hidden in the next screens. +// It is displayed with W (Double down arrow, special character from CGRAM) +// 01234567890123456789 +// >bttxt >bttxt >W +// Therefore at least some of the buttons, which can occur on the screen together, can only be 8-chars long max @@TODO. +// Beware - we only have space for 2 buttons on the LCD while the MMU has 3 buttons +// -> the left button on the MMU is not used/rendered on the LCD (it is also almost unused on the MMU side) + +// Used to parse the buttons from Btns(). +FSTR_P const btnOperation[] PROGMEM = { + GET_TEXT_F(MSG_BTN_RETRY), + GET_TEXT_F(MSG_DONE), + GET_TEXT_F(MSG_BTN_RESET_MMU), + GET_TEXT_F(MSG_BTN_UNLOAD), + GET_TEXT_F(MSG_BTN_LOAD), + GET_TEXT_F(MSG_BTN_EJECT), + GET_TEXT_F(MSG_TUNE), + GET_TEXT_F(MSG_BTN_STOP), + GET_TEXT_F(MSG_BTN_DISABLE_MMU) +}; + +// We have 8 different operations/buttons at this time, so we need at least 4 bits to encode each. +// Since one of the buttons is always "More", we can skip that one. +// Therefore we need just 1 byte to describe the necessary buttons for each screen. +uint8_t constexpr Btns(ButtonOperations bMiddle, ButtonOperations bRight) { + return ((uint8_t)bRight) << 4 | ((uint8_t)bMiddle); +} + +static const uint8_t errorButtons[] PROGMEM = { + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // FINDA_DIDNT_TRIGGER + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // FINDA_FILAMENT_STUCK + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // FSENSOR_DIDNT_TRIGGER + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // FSENSOR_FILAMENT_STUCK + + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // PULLEY_CANNOT_MOVE + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // FSENSOR_TOO_EARLY + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // INSPECT_FINDA + Btns(ButtonOperations::Continue, ButtonOperations::NoOperation), // LOAD_TO_EXTRUDER_FAILED + Btns(ButtonOperations::Retry, ButtonOperations::Tune), // SELECTOR_CANNOT_HOME + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // SELECTOR_CANNOT_MOVE + Btns(ButtonOperations::Retry, ButtonOperations::Tune), // IDLER_CANNOT_HOME + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // IDLER_CANNOT_MOVE + + Btns(ButtonOperations::Continue, ButtonOperations::ResetMMU), // WARNING_TMC_PULLEY_TOO_HOT + Btns(ButtonOperations::Continue, ButtonOperations::ResetMMU), // WARNING_TMC_SELECTOR_TOO_HOT + Btns(ButtonOperations::Continue, ButtonOperations::ResetMMU), // WARNING_TMC_IDLER_TOO_HOT + + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_PULLEY_OVERHEAT_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_SELECTOR_OVERHEAT_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_IDLER_OVERHEAT_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_PULLEY_DRIVER_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_SELECTOR_DRIVER_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_IDLER_DRIVER_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_PULLEY_DRIVER_RESET + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_SELECTOR_DRIVER_RESET + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_IDLER_DRIVER_RESET + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_PULLEY_UNDERVOLTAGE_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_SELECTOR_UNDERVOLTAGE_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_IDLER_UNDERVOLTAGE_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_PULLEY_DRIVER_SHORTED + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_SELECTOR_DRIVER_SHORTED + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // TMC_IDLER_DRIVER_SHORTED + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // MMU_PULLEY_SELFTEST_FAILED + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // MMU_SELECTOR_SELFTEST_FAILED + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // MMU_IDLER_SELFTEST_FAILED + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // MMU_MCU_ERROR + Btns(ButtonOperations::ResetMMU, ButtonOperations::DisableMMU), // MMU_NOT_RESPONDING + Btns(ButtonOperations::ResetMMU, ButtonOperations::DisableMMU), // COMMUNICATION_ERROR + + Btns(ButtonOperations::Unload, ButtonOperations::Continue), // FILAMENT_ALREADY_LOADED + Btns(ButtonOperations::StopPrint, ButtonOperations::ResetMMU), // INVALID_TOOL + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // QUEUE_FULL + Btns(ButtonOperations::ResetMMU, ButtonOperations::DisableMMU), // FW_UPDATE_NEEDED + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // FW_RUNTIME_ERROR + Btns(ButtonOperations::Retry, ButtonOperations::NoOperation), // UNLOAD_MANUALLY + Btns(ButtonOperations::Continue, ButtonOperations::NoOperation), // FILAMENT_EJECTED + Btns(ButtonOperations::Eject, ButtonOperations::Load), // FILAMENT_CHANGE + Btns(ButtonOperations::ResetMMU, ButtonOperations::NoOperation), // UNKOWN_ERROR +}; + +static_assert(COUNT(errorCodes) == COUNT(errorDescs)); +static_assert(COUNT(errorCodes) == COUNT(errorTitles)); +static_assert(COUNT(errorCodes) == COUNT(errorButtons)); + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/mmu_hw/progress_codes.h b/Marlin/src/feature/mmu3/mmu_hw/progress_codes.h new file mode 100644 index 0000000000..16e63a8564 --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu_hw/progress_codes.h @@ -0,0 +1,72 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * progress_codes.h + */ + +#include + +/** + * A complete set of progress codes which may be reported while running a high-level command/operation. + * This header file should be included in the printer's firmware as well as a reference, so the progress + * codes are extracted to one place. + */ +enum class ProgressCode : uint_fast8_t { + OK = 0, //!< finished ok + + EngagingIdler, // P1 + DisengagingIdler, // P2 + UnloadingToFinda, // P3 + UnloadingToPulley, // P4 + FeedingToFinda, // P5 + FeedingToExtruder, // P6 + FeedingToNozzle, // P7 + AvoidingGrind, // P8 + FinishingMoves, // P9 + + ERRDisengagingIdler, // P10 + ERREngagingIdler, // P11 + ERRWaitingForUser, // P12 + ERRInternal, // P13 + ERRHelpingFilament, // P14 + ERRTMCFailed, // P15 + + UnloadingFilament, // P16 + LoadingFilament, // P17 + SelectingFilamentSlot, // P18 + PreparingBlade, // P19 + PushingFilament, // P20 + PerformingCut, // P21 + ReturningSelector, // P22 + ParkingSelector, // P23 + EjectingFilament, // P24 + RetractingFromFinda, // P25 + + Homing, // P26 + MovingSelector, // P27 + + FeedingToFSensor, // P28 + + Empty = 0xFF // dummy empty state +}; diff --git a/Marlin/src/feature/mmu3/mmu_hw/registers.h b/Marlin/src/feature/mmu3/mmu_hw/registers.h new file mode 100644 index 0000000000..3e423c479d --- /dev/null +++ b/Marlin/src/feature/mmu3/mmu_hw/registers.h @@ -0,0 +1,70 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * registers.h + */ + +#include + +namespace MMU3 { + +// Register map for MMU +enum class Register : uint8_t { + Project_Major = 0x00, + Project_Minor = 0x01, + Project_Revision = 0x02, + Project_Build_Number = 0x03, + MMU_Errors = 0x04, + Current_Progress_Code = 0x05, + Current_Error_Code = 0x06, + Filament_State = 0x07, + FINDA_State = 0x08, + FSensor_State = 0x09, + Motor_Mode = 0x0A, + Extra_Load_Distance = 0x0B, + FSensor_Unload_Check_Distance = 0xC, + Pulley_Unload_Feedrate = 0x0D, + Pulley_Acceleration = 0x0E, + Selector_Acceleration = 0x0F, + Idler_Acceleration = 0x10, + Pulley_Load_Feedrate = 0x11, + Selector_Nominal_Feedrate = 0x12, + Idler_Nominal_Feedrate = 0x13, + Pulley_Slow_Feedrate = 0x14, + Selector_Homing_Feedrate = 0x15, + Idler_Homing_Feedrate = 0x16, + Pulley_sg_thrs_R = 0x17, + Selector_sg_thrs_R = 0x18, + Idler_sg_thrs_R = 0x19, + Get_Pulley_Position = 0x1A, + Set_Get_Selector_Slot = 0x1B, + Set_Get_Idler_Slot = 0x1C, + Set_Get_Selector_Cut_iRun = 0x1D, + Set_Get_Pulley_iRun = 0x1E, + Set_Get_Selector_iRun = 0x1F, + Set_Get_Idler_iRun = 0x20, + Reserved = 0x21, +}; + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/registers.h b/Marlin/src/feature/mmu3/registers.h new file mode 100644 index 0000000000..3e423c479d --- /dev/null +++ b/Marlin/src/feature/mmu3/registers.h @@ -0,0 +1,70 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * registers.h + */ + +#include + +namespace MMU3 { + +// Register map for MMU +enum class Register : uint8_t { + Project_Major = 0x00, + Project_Minor = 0x01, + Project_Revision = 0x02, + Project_Build_Number = 0x03, + MMU_Errors = 0x04, + Current_Progress_Code = 0x05, + Current_Error_Code = 0x06, + Filament_State = 0x07, + FINDA_State = 0x08, + FSensor_State = 0x09, + Motor_Mode = 0x0A, + Extra_Load_Distance = 0x0B, + FSensor_Unload_Check_Distance = 0xC, + Pulley_Unload_Feedrate = 0x0D, + Pulley_Acceleration = 0x0E, + Selector_Acceleration = 0x0F, + Idler_Acceleration = 0x10, + Pulley_Load_Feedrate = 0x11, + Selector_Nominal_Feedrate = 0x12, + Idler_Nominal_Feedrate = 0x13, + Pulley_Slow_Feedrate = 0x14, + Selector_Homing_Feedrate = 0x15, + Idler_Homing_Feedrate = 0x16, + Pulley_sg_thrs_R = 0x17, + Selector_sg_thrs_R = 0x18, + Idler_sg_thrs_R = 0x19, + Get_Pulley_Position = 0x1A, + Set_Get_Selector_Slot = 0x1B, + Set_Get_Idler_Slot = 0x1C, + Set_Get_Selector_Cut_iRun = 0x1D, + Set_Get_Pulley_iRun = 0x1E, + Set_Get_Selector_iRun = 0x1F, + Set_Get_Idler_iRun = 0x20, + Reserved = 0x21, +}; + +} // MMU3 diff --git a/Marlin/src/feature/mmu3/sound.cpp b/Marlin/src/feature/mmu3/sound.cpp new file mode 100644 index 0000000000..63edd2dd5e --- /dev/null +++ b/Marlin/src/feature/mmu3/sound.cpp @@ -0,0 +1,203 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * sound.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + + //#include "backlight.h" + #include "../../libs/buzzer.h" + #include "sound.h" + + // eSOUND_MODE eSoundMode=e_SOUND_MODE_LOUD; + // doesn't matter if Sound_Init is called (i.e. the value is in the EEPROM) + // !?! eSOUND_MODE eSoundMode; in ultraldc.cpp :: cd_settings_menu() it appears as a local variable like this + eSOUND_MODE eSoundMode; // =e_SOUND_MODE_DEFAULT; + + + static void Sound_SaveMode(void); + static void Sound_DoSound_Echo(void); + static void Sound_DoSound_Prompt(void); + static void Sound_DoSound_Alert(bool bOnce); + static void Sound_DoSound_Encoder_Move(void); + static void Sound_DoSound_Blind_Alert(void); + + void Sound_Init(void) { + // SET_OUTPUT(BEEPER); + // eSoundMode = static_cast(eeprom_init_default_byte((uint8_t*)EEPROM_SOUND_MODE, e_SOUND_MODE_DEFAULT)); + } + + void Sound_SaveMode(void) { + // eeprom_update_byte((uint8_t*)EEPROM_SOUND_MODE,(uint8_t)eSoundMode); + } + + void Sound_CycleState(void) { + switch (eSoundMode) { + case e_SOUND_MODE_LOUD: eSoundMode = e_SOUND_MODE_ONCE; break; + case e_SOUND_MODE_ONCE: eSoundMode = e_SOUND_MODE_SILENT; break; + case e_SOUND_MODE_SILENT: eSoundMode = e_SOUND_MODE_BLIND; break; + case e_SOUND_MODE_BLIND: eSoundMode = e_SOUND_MODE_LOUD; break; + default: eSoundMode = e_SOUND_MODE_LOUD; + } + Sound_SaveMode(); + } + + // if critical is true then silent and once mode is ignored + void __attribute__((noinline)) Sound_MakeCustom(uint16_t ms, uint16_t tone_, bool critical) { + if (critical || eSoundMode != e_SOUND_MODE_SILENT) + //if (!tone_) { + // WRITE(BEEPER, HIGH); + // _delay(ms); + // WRITE(BEEPER, LOW); + //} + //else { + // _tone(BEEPER, tone_); + // _delay(ms); + // _noTone(BEEPER); + //} + BUZZ(ms, tone_); + } + + void Sound_MakeSound(eSOUND_TYPE eSoundType) { + switch (eSoundMode) { + case e_SOUND_MODE_LOUD: + if (eSoundType == e_SOUND_TYPE_ButtonEcho) + Sound_DoSound_Echo(); + if (eSoundType == e_SOUND_TYPE_StandardPrompt) + Sound_DoSound_Prompt(); + if (eSoundType == e_SOUND_TYPE_StandardAlert) + Sound_DoSound_Alert(false); + break; + case e_SOUND_MODE_ONCE: + if (eSoundType == e_SOUND_TYPE_ButtonEcho) + Sound_DoSound_Echo(); + if (eSoundType == e_SOUND_TYPE_StandardPrompt) + Sound_DoSound_Prompt(); + if (eSoundType == e_SOUND_TYPE_StandardAlert) + Sound_DoSound_Alert(true); + break; + case e_SOUND_MODE_SILENT: + if (eSoundType == e_SOUND_TYPE_StandardAlert) + Sound_DoSound_Alert(true); + break; + case e_SOUND_MODE_BLIND: + if (eSoundType == e_SOUND_TYPE_ButtonEcho) + Sound_DoSound_Echo(); + if (eSoundType == e_SOUND_TYPE_StandardPrompt) + Sound_DoSound_Prompt(); + if (eSoundType == e_SOUND_TYPE_StandardAlert) + Sound_DoSound_Alert(false); + if (eSoundType == e_SOUND_TYPE_EncoderMove) + Sound_DoSound_Encoder_Move(); + if (eSoundType == e_SOUND_TYPE_BlindAlert) + Sound_DoSound_Blind_Alert(); + break; + default: + break; + } + } + + static void Sound_DoSound_Blind_Alert(void) { + // backlight_wake(1); + uint8_t nI; + for (nI = 0; nI < 20; nI++) { + BUZZ(94, 404); + BUZZ(94, 0); + } + } + + static void Sound_DoSound_Encoder_Move(void) { + uint8_t nI; + for (nI = 0; nI < 5; nI++) { + BUZZ(75, 404); + BUZZ(75, 0); + } + } + + static void Sound_DoSound_Echo(void) { + uint8_t nI; + for (nI = 0; nI < 10; nI++) { + BUZZ(100, 404); + BUZZ(100, 0); + } + } + + static void Sound_DoSound_Prompt(void) { + // backlight_wake(2); + BUZZ(500, 404); + } + + static void Sound_DoSound_Alert(bool bOnce) { + uint8_t nI, nMax; + nMax = bOnce ? 1 : 3; + for (nI = 0; nI < nMax; nI++) { + BUZZ(200, 404); + BUZZ(500, 0); + } + } + + static int16_t constexpr CONTINOUS_BEEP_PERIOD = 2000; // in ms + // static ShortTimer beep_timer; // Timer to keep track of continous beeping + static bool bFirst; // true if the first beep has occurred, e_SOUND_MODE_ONCE + + // @brief Handles sound when waiting for user input + // the function must be non-blocking. It is up to the caller + // to call this function repeatedly. + // Make sure to call sound_wait_for_user_reset() when the user has clicked the knob + // Loud - should continuously beep + // Silent - should be silent + // Once - should beep once + // Assist/Blind - as loud with beep and click on knob rotation and press + void sound_wait_for_user() { + #if BEEPER > 0 + if (eSoundMode == e_SOUND_MODE_SILENT) return; + + // Handle case where only one beep is needed + if (eSoundMode == e_SOUND_MODE_ONCE) { + if (bFirst) return; + Sound_MakeCustom(80, 0, false); + bFirst = true; + } + + // Handle case where there should be continous beeps + if (beep_timer.expired_cont(CONTINOUS_BEEP_PERIOD)) { + beep_timer.start(); + if (eSoundMode == e_SOUND_MODE_LOUD) + Sound_MakeCustom(80, 0, false); + else + // Assist (lower volume sound) + Sound_MakeSound(e_SOUND_TYPE_ButtonEcho); + } + #endif // BEEPER > 0 + } + + // @brief Resets the global state of sound_wait_for_user() + void sound_wait_for_user_reset() { + // beep_timer.stop(); + bFirst = false; + } + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/sound.h b/Marlin/src/feature/mmu3/sound.h new file mode 100644 index 0000000000..f72e6ecafe --- /dev/null +++ b/Marlin/src/feature/mmu3/sound.h @@ -0,0 +1,69 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * sound.h + */ + +#include + +#define e_SOUND_MODE_NULL 0xFF +typedef enum : uint8_t { + e_SOUND_MODE_LOUD, + e_SOUND_MODE_ONCE, + e_SOUND_MODE_SILENT, + e_SOUND_MODE_BLIND +} eSOUND_MODE; + +#define e_SOUND_MODE_DEFAULT e_SOUND_MODE_LOUD + +typedef enum : uint8_t { + e_SOUND_TYPE_ButtonEcho, + e_SOUND_TYPE_EncoderEcho, + e_SOUND_TYPE_StandardPrompt, + e_SOUND_TYPE_StandardConfirm, + e_SOUND_TYPE_StandardWarning, + e_SOUND_TYPE_StandardAlert, + e_SOUND_TYPE_EncoderMove, + e_SOUND_TYPE_BlindAlert +} eSOUND_TYPE; + +typedef enum : uint8_t { + e_SOUND_CLASS_Echo, + e_SOUND_CLASS_Prompt, + e_SOUND_CLASS_Confirm, + e_SOUND_CLASS_Warning, + e_SOUND_CLASS_Alert +} eSOUND_CLASS; + +extern eSOUND_MODE eSoundMode; + +extern void Sound_Init(void); +extern void Sound_CycleState(void); +extern void Sound_MakeSound(eSOUND_TYPE eSoundType); +extern void Sound_MakeCustom(uint16_t ms, uint16_t tone_, bool critical); +void sound_wait_for_user(); +void sound_wait_for_user_reset(); + +//static void Sound_DoSound_Echo(void); +//static void Sound_DoSound_Prompt(void); diff --git a/Marlin/src/feature/mmu3/ultralcd.cpp b/Marlin/src/feature/mmu3/ultralcd.cpp new file mode 100644 index 0000000000..d3cd3d371e --- /dev/null +++ b/Marlin/src/feature/mmu3/ultralcd.cpp @@ -0,0 +1,211 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * ultralcd.cpp + */ + +#include "../../inc/MarlinConfigPre.h" + +#if HAS_PRUSA_MMU3 + +#include "mmu3.h" +#include "mmu3_marlin_macros.h" +#include "mmu_hw/errors_list.h" +#include "ultralcd.h" + +#include "../../lcd/menu/menu_item.h" +#include "../../gcode/gcode.h" +#include "../../lcd/marlinui.h" + +//! @brief Show a two-choice prompt on the last line of the LCD +//! @param selected Show first choice as selected if true, the second otherwise +//! @param first_choice text caption of first possible choice +//! @param second_choice text caption of second possible choice +//! @param second_col column on LCD where second choice is rendered. +//! @param third_choice text caption of third, optional, choice. +void lcd_show_choices_prompt_P(uint8_t selected, const char *first_choice, const char *second_choice, uint8_t second_col, const char *third_choice) { + lcd_put_lchar(0, 3, selected == LCD_LEFT_BUTTON_CHOICE ? '>' : ' '); + lcd_put_u8str(first_choice); + lcd_put_lchar(second_col, 3, selected == LCD_MIDDLE_BUTTON_CHOICE ? '>' : ' '); + lcd_put_u8str(second_choice); + if (third_choice) { + lcd_put_lchar(18, 3, selected == LCD_RIGHT_BUTTON_CHOICE ? '>' : ' '); + lcd_put_u8str(third_choice); + } +} + +void lcd_space(uint8_t n) { + while (n--) lcd_put_lchar(' '); +} + +// Print extruder status (5 chars total) +// Scenario 1: "F?" +// There is no filament loaded and no tool change is in progress +// Scenario 2: "F[nr.]" +// [nr.] ranges from 1 to 5. +// Shows which filament is loaded. No tool change is in progress +// Scenario 3: "?>[nr.]" +// [nr.] ranges from 1 to 5. +// There is no filament currently loaded, but [nr.] is currently being loaded via tool change +// Scenario 4: "[nr.]>?" +// [nr.] ranges from 1 to 5. +// This scenario indicates a bug in the firmware if ? is on the right side +// Scenario 5: "[nr1.]>[nr2.]" +// [nr1.] ranges from 1 to 5. +// [nr2.] ranges from 1 to 5. +// Filament [nr1.] was loaded, but [nr2.] is currently being loaded via tool change +// Scenario 6: "?>?" +// This scenario should not be possible and indicates a bug in the firmware +uint8_t lcdui_print_extruder(void) { + uint8_t chars = 1; + lcd_space(1); + if (mmu3.get_current_tool() == mmu3.get_tool_change_tool()) { + lcd_put_lchar('F'); + lcd_put_lchar(mmu3.get_current_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_current_tool() + '1'); + chars += 2; + } + else { + lcd_put_lchar(mmu3.get_current_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_current_tool() + '1'); + lcd_put_lchar('>'); + lcd_put_lchar(mmu3.get_tool_change_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_tool_change_tool() + '1'); + chars += 3; + } + return chars; +} + +bool is_whitespace_P(const char *c_addr) { + const char c = pgm_read_byte(c_addr); + return c == ' ' || c == '\t' || c == '\r' || c == '\n'; +} + +bool is_punctuation_P(const char *c_addr) { + const char c = pgm_read_byte(c_addr); + return c == '.' || c == ',' || c == ':' || c == ';' || c == '?' || c == '!' || c == '/'; +} + +/** + * @brief show full screen message + * + * This function is non-blocking + * @param msg message to be displayed from PROGMEM + * @return rest of the text (to be displayed on next page) + */ +static FSTR_P const lcd_display_message_fullscreen_async(FSTR_P const fmsg) { + PGM_P msg = FTOP(fmsg); + PGM_P msgend = msg; + //bool multi_screen = false; + for (uint8_t row = 0; row < LCD_HEIGHT; ++row) { + if (pgm_read_byte(msgend) == 0) break; + SETCURSOR(0, row); + + // Previous row ended with a complete word, so the first character in the + // next row is a whitespace. We can skip the whitespace on a new line. + if (is_whitespace_P(msg) && ++msg == nullptr) break; // End of the message. + + uint8_t linelen = (strlen_P(msg) > LCD_WIDTH) ? LCD_WIDTH : strlen_P(msg); + PGM_P const msgend2 = msg + linelen; + msgend = msgend2; + if (row == 3 && linelen == LCD_WIDTH) { + // Last line of the display, full line should be displayed. + // Find out, whether this message will be split into multiple screens. + //multi_screen = pgm_read_byte(msgend) != 0; + // We do not need this... + //if (multi_screen) msgend = (msgend2 -= 2); + } + if (pgm_read_byte(msgend) != 0 && !is_whitespace_P(msgend) && !is_punctuation_P(msgend)) { + // Splitting a word. Find the start of the current word. + while (msgend > msg && !is_whitespace_P(msgend - 1)) --msgend; + if (msgend == msg) msgend = msgend2; // Found a single long word, which cannot be split. Just cut it. + } + for (; msg < msgend; ++msg) { + const char c = char(pgm_read_byte(msg)); + if (c == '\n') { + // Abort early if '\n' is encountered. + // This character is used to force the following words to be printed on the next line. + break; + } + lcd_put_lchar(c); + } + } + return FPSTR(msgend); +} + +FSTR_P const lcd_display_message_fullscreen(FSTR_P const fmsg) { + // Disable update of the screen by the usual lcd_update(0) routine. + #if HAS_WIRED_LCD + //ui.lcdDrawUpdate = LCDViewAction::LCDVIEW_NONE; + ui.clear_lcd(); + return lcd_display_message_fullscreen_async(fmsg); + #else + return fmsg + #endif +} + +/** + * @brief show full screen message and wait + * + * This function is blocking. + * @param msg message to be displayed from PROGMEM + */ +void lcd_show_fullscreen_message_and_wait(FSTR_P const fmsg) { + LcdUpdateDisabler lcdUpdateDisabler; + FSTR_P fmsg_next = lcd_display_message_fullscreen(fmsg); + const bool multi_screen = fmsg_next != nullptr; + ui.use_click(); + KEEPALIVE_STATE(PAUSED_FOR_USER); + // Until confirmed by a button click. + for (;;) { + if (fmsg_next == nullptr) { + // Display the confirm char. + //lcd_put_lchar(LCD_WIDTH - 2, LCD_HEIGHT - 2, LCD_STR_CONFIRM[0]); + } + // Wait for 5 seconds before displaying the next text. + for (uint8_t i = 0; i < 100; ++i) { + marlin.idle(true); + safe_delay(50); + if (ui.use_click()) { + if (fmsg_next == nullptr) { + KEEPALIVE_STATE(IN_HANDLER); + return ui.go_back(); + } + if (!multi_screen) break; + if (fmsg_next == nullptr) fmsg_next = fmsg; + fmsg_next = lcd_display_message_fullscreen(fmsg_next); + } + } + //if (multi_screen) { + // if (fmsg_next == nullptr) fmsg_next = fmsg; + // fmsg_next = lcd_display_message_fullscreen(fmsg_next); + //} + } +} + +void lcd_replace_status_char(const uint8_t position, const char message) { + if (position >= MAX_MESSAGE_SIZE) return; + //int size = ui.status_message.length(); + char *str = ui.status_message.buffer(); + str[position] = message; + ui.refresh(LCDVIEW_REDRAW_NOW); // force redraw +} + +#endif // HAS_PRUSA_MMU3 diff --git a/Marlin/src/feature/mmu3/ultralcd.h b/Marlin/src/feature/mmu3/ultralcd.h new file mode 100644 index 0000000000..e7f06dfb1f --- /dev/null +++ b/Marlin/src/feature/mmu3/ultralcd.h @@ -0,0 +1,72 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General 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 + +/** + * ultralcd.h + */ + +#include "../../MarlinCore.h" +#include "../../lcd/marlinui.h" + +#define LCD_LEFT_BUTTON_CHOICE 0 +#define LCD_MIDDLE_BUTTON_CHOICE 1 +#define LCD_RIGHT_BUTTON_CHOICE 2 + +#define LCD_STR_ARROW_2_DOWN "\x88" +#define LCD_STR_CONFIRM "\x89" +#define LCD_STR_SOLID_BLOCK "\xFF" // from the default character set + +/** + * @brief Helper class to temporarily disable LCD updates + * + * When constructed (on stack), original state state of lcd_update_enabled is stored + * and LCD updates are disabled. + * When destroyed (gone out of scope), original state of LCD update is restored. + * It has zero overhead compared to storing bool saved = lcd_update_enabled + * and calling lcd_update_enable(false) and lcd_update_enable(saved). + */ +class LcdUpdateDisabler { + public: + LcdUpdateDisabler() : m_updateEnabled(ui.lcdDrawUpdate) { + TERN_(HAS_WIRED_LCD, ui.refresh(LCDViewAction::LCDVIEW_NONE)); + } + ~LcdUpdateDisabler() { + #if HAS_WIRED_LCD + ui.refresh(m_updateEnabled); + ui.clear_lcd(); + ui.update(); + #endif + } + + private: + LCDViewAction m_updateEnabled; +}; + +bool is_whitespace_P(const char *c_addr); +bool is_punctuation_P(const char *c_addr); +FSTR_P const lcd_display_message_fullscreen(FSTR_P const pmsg); +void lcd_show_choices_prompt_P(uint8_t selected, const char *first_choice, const char *second_choice, uint8_t second_col, const char *third_choice=nullptr); +void lcd_show_fullscreen_message_and_wait(FSTR_P const fmsg); +uint8_t lcdui_print_extruder(void); +void lcd_space(uint8_t n); +void lcd_replace_status_char(uint8_t position, const char message); diff --git a/Marlin/src/feature/password/password.cpp b/Marlin/src/feature/password/password.cpp index 1d376cc586..d36b3edd09 100644 --- a/Marlin/src/feature/password/password.cpp +++ b/Marlin/src/feature/password/password.cpp @@ -36,7 +36,7 @@ uint32_t Password::value, Password::value_entry; // // Authenticate user with password. -// Called from Setup, after SD Prinitng Stops/Aborts, and M510 +// Called from Setup, after SD Printing Stops/Aborts, and M510 // void Password::lock_machine() { is_locked = true; diff --git a/Marlin/src/feature/password/password.h b/Marlin/src/feature/password/password.h index 208765b212..0f8bc28bd8 100644 --- a/Marlin/src/feature/password/password.h +++ b/Marlin/src/feature/password/password.h @@ -37,6 +37,8 @@ public: static void access_menu_password(); static void authentication_done(); static void media_gatekeeper(); + static void media_gatekeeper_sd(); + static void media_gatekeeper_usb(); private: static void authenticate_user(const screenFunc_t, const screenFunc_t); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 1c2ea59d4d..025bcb8383 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -23,6 +23,8 @@ /** * feature/pause.cpp - Pause feature support functions * This may be combined with related G-codes if features are consolidated. + * + * Note: Calls to ui.pause_show_message are passed to either ExtUI or MarlinUI. */ #include "../inc/MarlinConfigPre.h" @@ -60,8 +62,8 @@ #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_LCD_PROUI) - #include "../lcd/e3v2/proui/dwin.h" +#elif ENABLED(SOVOL_SV06_RTS) + #include "../lcd/sovol_rts/sovol_rts.h" #endif #include "../lcd/marlinui.h" @@ -89,9 +91,11 @@ static xyze_pos_t resume_position; PauseMode pause_mode = PAUSE_MODE_PAUSE_PRINT; #endif -fil_change_settings_t fc_settings[EXTRUDERS]; +#if ENABLED(CONFIGURE_FILAMENT_CHANGE) + fil_change_settings_t fc_settings[EXTRUDERS]; +#endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../sd/cardreader.h" #endif @@ -146,15 +150,20 @@ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=P thermalManager.setTargetHotend(thermalManager.extrude_min_temp, active_extruder); #endif - ui.pause_show_message(PAUSE_MESSAGE_HEATING, mode); UNUSED(mode); + ui.pause_show_message(PAUSE_MESSAGE_HEATING, mode); + + #if ENABLED(SOVOL_SV06_RTS) + rts.gotoPage(ID_Cold_L, ID_Cold_D); + rts.updateTempE0(); + #endif if (wait) return thermalManager.wait_for_hotend(active_extruder); // Allow interruption by Emergency Parser M108 - wait_for_heatup = TERN1(PREVENT_COLD_EXTRUSION, !thermalManager.allow_cold_extrude); - while (wait_for_heatup && ABS(thermalManager.wholeDegHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > (TEMP_WINDOW)) - idle(); - wait_for_heatup = false; + marlin.wait_for_heatup = TERN1(PREVENT_COLD_EXTRUSION, !thermalManager.allow_cold_extrude); + while (marlin.is_heating() && ABS(thermalManager.wholeDegHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > (TEMP_WINDOW)) + marlin.idle(); + marlin.heatup_done(); #if ENABLED(PREVENT_COLD_EXTRUSION) // A user can cancel wait-for-heating with M108 @@ -179,10 +188,8 @@ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=P * * Returns 'true' if load was completed, 'false' for abort */ -bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load_length/*=0*/, const_float_t purge_length/*=0*/, const int8_t max_beep_count/*=0*/, - const bool show_lcd/*=false*/, const bool pause_for_user/*=false*/, - const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ - DXC_ARGS +bool load_filament(const float slow_load_length/*=0*/, const float fast_load_length/*=0*/, const float purge_length/*=0*/, const int8_t max_beep_count/*=0*/, + const bool show_lcd/*=false*/, const bool pause_for_user/*=false*/, const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ DXC_ARGS ) { DEBUG_SECTION(lf, "load_filament", true); DEBUG_ECHOLNPGM("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " showlcd:", show_lcd, " pauseforuser:", pause_for_user, " pausemode:", mode DXC_SAY); @@ -199,28 +206,28 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load first_impatient_beep(max_beep_count); KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this + marlin.wait_start(); // LCD click or M108 will clear this - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("Load Filament"))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENTLOAD))); #if ENABLED(HOST_PROMPT_SUPPORT) const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, active_extruder); hostui.prompt_do(PROMPT_USER_CONTINUE, F("Load Filament T"), tool, FPSTR(CONTINUE_STR)); #endif - while (wait_for_user) { + while (marlin.wait_for_user) { impatient_beep(max_beep_count); - #if BOTH(FILAMENT_CHANGE_RESUME_ON_INSERT, FILAMENT_RUNOUT_SENSOR) - #if ENABLED(MULTI_FILAMENT_SENSOR) - #define _CASE_INSERTED(N) case N-1: if (READ(FIL_RUNOUT##N##_PIN) != FIL_RUNOUT##N##_STATE) wait_for_user = false; break; + #if ALL(HAS_FILAMENT_SENSOR, FILAMENT_CHANGE_RESUME_ON_INSERT) + #if MULTI_FILAMENT_SENSOR + #define _CASE_INSERTED(N) case N-1: if (!FILAMENT_IS_OUT(N)) marlin.user_resume(); break; switch (active_extruder) { REPEAT_1(NUM_RUNOUT_SENSORS, _CASE_INSERTED) } #else - if (READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_STATE) wait_for_user = false; + if (!FILAMENT_IS_OUT()) marlin.user_resume(); #endif #endif - idle_no_sleep(); + marlin.idle_no_sleep(); } } @@ -234,6 +241,8 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load TERN_(BELTPRINTER, do_blocking_move_to_xy(0.00, 50.00)); + TERN_(MPCTEMP, MPC::e_paused = true); + // Slow Load filament if (slow_load_length) unscaled_e_move(slow_load_length, FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE); @@ -260,11 +269,11 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE))); - TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE), FPSTR(CONTINUE_STR))); - wait_for_user = true; // A click or M108 breaks the purge_length loop - for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) + TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE))); + marlin.wait_start(); // A click or M108 breaks the purge_length loop + for (float purge_count = purge_length; purge_count > 0 && marlin.wait_for_user; --purge_count) unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); - wait_for_user = false; + marlin.user_resume(); #else @@ -273,6 +282,11 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load // "Wait for filament purge" if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE); + #if ENABLED(SOVOL_SV06_RTS) + rts.updateTempE0(); + rts.gotoPage(ID_Purge_L, ID_Purge_D); + #endif + // Extrude filament to get into hotend unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); } @@ -283,13 +297,14 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load if (show_lcd) { // Show "Purge More" / "Resume" menu and wait for reply KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = false; - #if EITHER(HAS_MARLINUI_MENU, DWIN_LCD_PROUI) - ui.pause_show_message(PAUSE_MESSAGE_OPTION); // Also sets PAUSE_RESPONSE_WAIT_FOR + marlin.user_resume(); + pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) + ui.pause_show_message(PAUSE_MESSAGE_OPTION); // MarlinUI and MKS UI also set PAUSE_RESPONSE_WAIT_FOR #else - pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; + TERN_(SOVOL_SV06_RTS, rts.gotoPage(ID_PurgeMore_L, ID_PurgeMore_D)); #endif - while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) idle_no_sleep(); + while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) marlin.idle_no_sleep(); } #endif @@ -297,6 +312,9 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load } while (TERN0(M600_PURGE_MORE_RESUMABLE, pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE)); #endif + + TERN_(MPCTEMP, MPC::e_paused = false); + TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_end()); return true; @@ -324,20 +342,20 @@ inline void disable_active_extruder() { * * Returns 'true' if unload was completed, 'false' for abort */ -bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/, +bool unload_filament(const float unload_length, const bool show_lcd/*=false*/, const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) - , const_float_t mix_multiplier/*=1.0*/ + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + , const float mix_multiplier/*=1.0*/ #endif ) { DEBUG_SECTION(uf, "unload_filament", true); DEBUG_ECHOLNPGM("... unloadlen:", unload_length, " showlcd:", show_lcd, " mode:", mode - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , " mixmult:", mix_multiplier #endif ); - #if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if !ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) constexpr float mix_multiplier = 1.0f; #endif @@ -348,6 +366,11 @@ bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/, if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_UNLOAD, mode); + #if ENABLED(SOVOL_SV06_RTS) + rts.updateTempE0(); + rts.gotoPage(ID_Unload_L, ID_Unload_D); + #endif + // Retract filament unscaled_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier); @@ -393,12 +416,10 @@ bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/, */ uint8_t did_pause_print = 0; -bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool show_lcd/*=false*/, const_float_t unload_length/*=0*/ DXC_ARGS) { +bool pause_print(const float retract, const xyz_pos_t &park_point, const bool show_lcd/*=false*/, const float unload_length/*=0*/ DXC_ARGS) { DEBUG_SECTION(pp, "pause_print", true); DEBUG_ECHOLNPGM("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", show_lcd DXC_SAY); - UNUSED(show_lcd); - if (did_pause_print) return false; // already paused #if ENABLED(HOST_ACTION_COMMANDS) @@ -410,14 +431,13 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool #endif TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_open(PROMPT_INFO, F("Pause"), FPSTR(DISMISS_STR))); - TERN_(DWIN_LCD_PROUI, DWIN_Print_Pause()); // Indicate that the printer is paused ++did_pause_print; // Pause the print job and timer - #if ENABLED(SDSUPPORT) - const bool was_sd_printing = IS_SD_PRINTING(); + #if HAS_MEDIA + const bool was_sd_printing = card.isStillPrinting(); if (was_sd_printing) { card.pauseSDPrint(); ++did_pause_print; // Indicate SD pause also @@ -441,7 +461,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool // Wait for buffered blocks to complete planner.synchronize(); - #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN + #if ALL(ADVANCED_PAUSE_FANS_PAUSE, HAS_FAN) thermalManager.set_fans_paused(true); #endif @@ -461,6 +481,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool // If axes don't need to home then the nozzle can park if (do_park) nozzle.park(0, park_point); // Park the nozzle by doing a Minimum Z Raise followed by an XY Move + if (!do_park) LCD_MESSAGE(MSG_PARK_FAILED); #if ENABLED(DUAL_X_CARRIAGE) const int8_t saved_ext = active_extruder; @@ -472,9 +493,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool if (unload_length) unload_filament(unload_length, show_lcd, PAUSE_MODE_CHANGE_FILAMENT); - #if ENABLED(DUAL_X_CARRIAGE) - set_duplication_enabled(saved_ext_dup_mode, saved_ext); - #endif + TERN_(DUAL_X_CARRIAGE, set_duplication_enabled(saved_ext_dup_mode, saved_ext)); // Disable the Extruder for manual change disable_active_extruder(); @@ -500,8 +519,13 @@ void show_continue_prompt(const bool is_reload) { DEBUG_ECHOLNPGM("... is_reload:", is_reload); ui.pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING); + #if ENABLED(SOVOL_SV06_RTS) + rts.updateTempE0(); + rts.gotoPage(ID_Insert_L, ID_Insert_D); + rts.sendData(Beep, SoundAddr); + #endif SERIAL_ECHO_START(); - SERIAL_ECHOF(is_reload ? F(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : F(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); + SERIAL_ECHO(is_reload ? F(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : F(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); } void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) { @@ -527,10 +551,10 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for filament insert by user and press button KEEPALIVE_STATE(PAUSED_FOR_USER); - TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_NOZZLE_PARKED), FPSTR(CONTINUE_STR))); + TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_NOZZLE_PARKED))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_NOZZLE_PARKED))); - wait_for_user = true; // LCD click or M108 will clear this - while (wait_for_user) { + marlin.wait_start(); // LCD click or M108 will clear this + while (marlin.wait_for_user) { impatient_beep(max_beep_count); // If the nozzle has timed out... @@ -541,19 +565,25 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // re-heat the nozzle, re-show the continue prompt, restart idle timers, start over if (nozzle_timed_out) { ui.pause_show_message(PAUSE_MESSAGE_HEAT); + #if ENABLED(SOVOL_SV06_RTS) + rts.updateTempE0(); + rts.gotoPage(ID_HeatNozzle_L, ID_HeatNozzle_D); + #endif SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT)); TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_HEATER_TIMEOUT), GET_TEXT_F(MSG_REHEAT))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_HEATER_TIMEOUT))); + #if ENABLED(TOUCH_UI_FTDI_EVE) + ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FTDI_HEATER_TIMEOUT)); + #elif ENABLED(EXTENSIBLE_UI) + ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_HEATER_TIMEOUT)); + #endif - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(0, true)); // Wait for LCD click or M108 + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response(0, true)); // Wait for LCD click or M108 TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_INFO, GET_TEXT_F(MSG_REHEATING))); - TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(GET_TEXT_F(MSG_REHEATING))); - - TERN_(DWIN_LCD_PROUI, LCD_MESSAGE(MSG_REHEATING)); + LCD_MESSAGE(MSG_REHEATING); // Re-enable the heaters if they timed out HOTEND_LOOP() thermalManager.reset_hotend_idle_timer(e); @@ -569,20 +599,21 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); - TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_REHEATDONE), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_REHEATDONE))); - TERN_(DWIN_LCD_PROUI, LCD_MESSAGE(MSG_REHEATDONE)); + TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_REHEATDONE))); + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_REHEATDONE)); + #else + LCD_MESSAGE(MSG_REHEATDONE); + #endif - IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, wait_for_user = true); + IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, marlin.wait_start()); nozzle_timed_out = false; first_impatient_beep(max_beep_count); } - idle_no_sleep(); + marlin.idle_no_sleep(); } - #if ENABLED(DUAL_X_CARRIAGE) - set_duplication_enabled(saved_ext_dup_mode, saved_ext); - #endif + TERN_(DUAL_X_CARRIAGE, set_duplication_enabled(saved_ext_dup_mode, saved_ext)); } /** @@ -605,9 +636,27 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep * - Send host action for resume, if configured * - Resume the current SD print job, if any */ -void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_length/*=0*/, const_float_t purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, const celsius_t targetTemp/*=0*/ DXC_ARGS) { +void resume_print( + const float slow_load_length/*=0*/, + const float fast_load_length/*=0*/, + const float purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, + const int8_t max_beep_count/*=0*/, + const celsius_t targetTemp/*=0*/, + const bool show_lcd/*=true*/, + const bool pause_for_user/*=false*/ + DXC_ARGS +) { DEBUG_SECTION(rp, "resume_print", true); - DEBUG_ECHOLNPGM("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " targetTemp:", targetTemp DXC_SAY); + DEBUG_ECHOLNPGM( + "... slowlen:", slow_load_length + , " fastlen:", fast_load_length + , " purgelen:", purge_length + , " maxbeep:", max_beep_count + , " targetTemp:", targetTemp + , " show_lcd:", show_lcd + , " pause_for_user:", pause_for_user + DXC_SAY + ); /* SERIAL_ECHOLNPGM( @@ -621,7 +670,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ if (!did_pause_print) return; // Re-enable the heaters if they timed out - bool nozzle_timed_out = false; + bool nozzle_timed_out = pause_for_user; HOTEND_LOOP() { nozzle_timed_out |= thermalManager.heater_idle[e].timed_out; thermalManager.reset_hotend_idle_timer(e); @@ -631,7 +680,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ thermalManager.setTargetHotend(targetTemp, active_extruder); // Load the new filament - load_filament(slow_load_length, fast_load_length, purge_length, max_beep_count, true, nozzle_timed_out, PAUSE_MODE_SAME DXC_PASS); + load_filament(slow_load_length, fast_load_length, purge_length, max_beep_count, show_lcd, nozzle_timed_out, PAUSE_MODE_SAME DXC_PASS); if (targetTemp > 0) { thermalManager.setTargetHotend(targetTemp, active_extruder); @@ -685,6 +734,12 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ planner.set_e_position_mm((destination.e = current_position.e = resume_position.e)); ui.pause_show_message(PAUSE_MESSAGE_STATUS); + #if ENABLED(SOVOL_SV06_RTS) + if (pause_flag) + rts.gotoPage(ID_PrintResume_L, ID_PrintResume_D); + else + rts.refreshTime(); + #endif #ifdef ACTION_ON_RESUMED hostui.resumed(); @@ -699,7 +754,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ // Resume the print job timer if it was running if (print_job_timer.isPaused()) print_job_timer.start(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (did_pause_print) { --did_pause_print; card.startOrResumeFilePrinting(); @@ -714,13 +769,8 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ TERN_(HAS_FILAMENT_SENSOR, runout.reset()); - #if ENABLED(DWIN_LCD_PROUI) - DWIN_Print_Resume(); - HMI_ReturnScreen(); - #else - ui.reset_status(); - ui.return_to_status(); - #endif + ui.reset_status(); + ui.return_to_status(); } #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index 134b1d1b32..4fbb108180 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -26,10 +26,6 @@ * This may be combined with related G-codes if features are consolidated. */ -typedef struct { - float unload_length, load_length; -} fil_change_settings_t; - #include "../inc/MarlinConfigPre.h" #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -48,18 +44,20 @@ enum PauseMessage : char { PAUSE_MESSAGE_PARKING, PAUSE_MESSAGE_CHANGING, PAUSE_MESSAGE_WAITING, - PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_INSERT, PAUSE_MESSAGE_LOAD, + PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_PURGE, PAUSE_MESSAGE_OPTION, PAUSE_MESSAGE_RESUME, - PAUSE_MESSAGE_STATUS, PAUSE_MESSAGE_HEAT, - PAUSE_MESSAGE_HEATING + PAUSE_MESSAGE_HEATING, + PAUSE_MESSAGE_STATUS, + PAUSE_MESSAGE_COUNT }; #if M600_PURGE_MORE_RESUMABLE + // Input methods can Purge More, Resume, or request input enum PauseMenuResponse : char { PAUSE_RESPONSE_WAIT_FOR, PAUSE_RESPONSE_EXTRUDE_MORE, @@ -69,7 +67,20 @@ enum PauseMessage : char { extern PauseMode pause_mode; #endif -extern fil_change_settings_t fc_settings[EXTRUDERS]; +typedef struct FilamentChangeSettings { + #if ENABLED(CONFIGURE_FILAMENT_CHANGE) + float load_length, unload_length; + #else + static constexpr float load_length = FILAMENT_CHANGE_FAST_LOAD_LENGTH, + unload_length = FILAMENT_CHANGE_UNLOAD_LENGTH; + #endif +} fil_change_settings_t; + +#if ENABLED(CONFIGURE_FILAMENT_CHANGE) + extern fil_change_settings_t fc_settings[EXTRUDERS]; +#else + constexpr fil_change_settings_t fc_settings[EXTRUDERS]; +#endif extern uint8_t did_pause_print; @@ -80,10 +91,10 @@ extern uint8_t did_pause_print; // Pause the print. If unload_length is set, do a Filament Unload bool pause_print( - const_float_t retract, // (mm) Retraction length + const float retract, // (mm) Retraction length const xyz_pos_t &park_point, // Parking XY Position and Z Raise const bool show_lcd=false, // Set LCD status messages? - const_float_t unload_length=0 // (mm) Filament Change Unload Length - 0 to skip + const float unload_length=0 // (mm) Filament Change Unload Length - 0 to skip DXC_PARAMS // Dual-X-Carriage extruder index ); @@ -94,18 +105,20 @@ void wait_for_confirmation( ); void resume_print( - const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move - const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move - const_float_t extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, // (mm) Purge length + const float slow_load_length=0, // (mm) Slow Load Length for finishing move + const float fast_load_length=0, // (mm) Fast Load Length for initial move + const float purge_length=ADVANCED_PAUSE_PURGE_LENGTH, // (mm) Purge length const int8_t max_beep_count=0, // Beep alert for attention - const celsius_t targetTemp=0 // (°C) A target temperature for the hotend + const celsius_t targetTemp=0, // (°C) A target temperature for the hotend + const bool show_lcd=true, // Set LCD status messages? + const bool pause_for_user=false // Pause for user before returning? DXC_PARAMS // Dual-X-Carriage extruder index ); bool load_filament( - const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move - const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move - const_float_t extrude_length=0, // (mm) Purge length + const float slow_load_length=0, // (mm) Slow Load Length for finishing move + const float fast_load_length=0, // (mm) Fast Load Length for initial move + const float purge_length=0, // (mm) Purge length const int8_t max_beep_count=0, // Beep alert for attention const bool show_lcd=false, // Set LCD status messages? const bool pause_for_user=false, // Pause for user before returning? @@ -114,11 +127,11 @@ bool load_filament( ); bool unload_filament( - const_float_t unload_length, // (mm) Filament Unload Length - 0 to skip + const float unload_length, // (mm) Filament Unload Length - 0 to skip const bool show_lcd=false, // Set LCD status messages? const PauseMode mode=PAUSE_MODE_PAUSE_PRINT // Pause Mode to apply - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) - , const_float_t mix_multiplier=1.0f // Extrusion multiplier (for a Mixing Extruder) + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + , const float mix_multiplier=1.0f // Extrusion multiplier (for a Mixing Extruder) #endif ); diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 8a16628bac..2068558fe9 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -26,7 +26,7 @@ #include "../inc/MarlinConfigPre.h" -#if EITHER(PSU_CONTROL, AUTO_POWER_CONTROL) +#if ANY(PSU_CONTROL, AUTO_POWER_CONTROL) #include "power.h" #include "../module/planner.h" @@ -34,6 +34,10 @@ #include "../module/temperature.h" #include "../MarlinCore.h" +#if ENABLED(MAX7219_REINIT_ON_POWERUP) + #include "max7219.h" +#endif + #if ENABLED(PS_OFF_SOUND) #include "../libs/buzzer.h" #endif @@ -49,13 +53,21 @@ bool Power::psu_on; #include "../module/stepper.h" #include "../module/temperature.h" - #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) + #if ALL(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) #include "controllerfan.h" #endif + #if ANY(LASER_FEATURE, SPINDLE_FEATURE) + #include "spindle_laser.h" + #endif + millis_t Power::lastPowerOn; #endif +#if PSU_TRACK_STATE_MS + millis_t Power::last_state_change_ms = 0; +#endif + /** * Initialize pins & state for the power manager. * @@ -78,14 +90,23 @@ void Power::power_on() { if (psu_on) return; - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) cancelAutoPowerOff(); #endif OUT_WRITE(PS_ON_PIN, PSU_ACTIVE_STATE); + #if ENABLED(PSU_OFF_REDUNDANT) + OUT_WRITE(PS_ON1_PIN, TERN_(PSU_OFF_REDUNDANT_INVERTED, !)PSU_ACTIVE_STATE); + #endif + TERN_(PSU_TRACK_STATE_MS, last_state_change_ms = millis()); + psu_on = true; safe_delay(PSU_POWERUP_DELAY); + restore_stepper_drivers(); + + TERN_(MAX7219_REINIT_ON_POWERUP, max7219.init()); + TERN_(HAS_TRINAMIC_CONFIG, safe_delay(PSU_POWERUP_DELAY)); #ifdef PSU_POWERUP_GCODE @@ -98,12 +119,12 @@ void Power::power_on() { * Processes any PSU_POWEROFF_GCODE and makes a PS_OFF_SOUND if enabled. */ void Power::power_off() { - SERIAL_ECHOLNPGM(STR_POWEROFF); - - TERN_(HAS_SUICIDE, suicide()); + TERN_(HAS_SUICIDE, marlin.suicide()); if (!psu_on) return; + SERIAL_ECHOLNPGM(STR_POWEROFF); + #ifdef PSU_POWEROFF_GCODE gcode.process_subcommands_now(F(PSU_POWEROFF_GCODE)); #endif @@ -113,14 +134,19 @@ void Power::power_off() { #endif OUT_WRITE(PS_ON_PIN, !PSU_ACTIVE_STATE); + #if ENABLED(PSU_OFF_REDUNDANT) + OUT_WRITE(PS_ON1_PIN, IF_DISABLED(PSU_OFF_REDUNDANT_INVERTED, !)PSU_ACTIVE_STATE); + #endif + TERN_(PSU_TRACK_STATE_MS, last_state_change_ms = millis()); + psu_on = false; - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) cancelAutoPowerOff(); #endif } -#if EITHER(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) +#if ANY(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) bool Power::is_cooling_needed() { #if HAS_HOTEND && AUTO_POWER_E_TEMP @@ -140,7 +166,7 @@ void Power::power_off() { #endif -#if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) +#if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) #if ENABLED(POWER_OFF_TIMER) millis_t Power::power_off_time = 0; @@ -175,14 +201,14 @@ void Power::power_off() { /** * Check all conditions that would signal power needing to be on. * - * @returns bool if power is needed + * @return bool if power is needed */ bool Power::is_power_needed() { // If any of the stepper drivers are enabled... if (stepper.axis_enabled.bits) return true; - if (printJobOngoing() || printingIsPaused()) return true; + if (marlin.printJobOngoing() || marlin.printingIsPaused()) return true; #if ENABLED(AUTO_POWER_FANS) FANS_LOOP(i) if (thermalManager.fan_speed[i]) return true; @@ -192,10 +218,14 @@ void Power::power_off() { HOTEND_LOOP() if (thermalManager.autofan_speed[e]) return true; #endif - #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) + #if ALL(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) if (controllerFan.state()) return true; #endif + #if ANY(LASER_FEATURE, SPINDLE_FEATURE) + if (TERN0(AUTO_POWER_SPINDLE_LASER, cutter.enabled())) return true; + #endif + if (TERN0(AUTO_POWER_CHAMBER_FAN, thermalManager.chamberfan_speed)) return true; @@ -231,7 +261,7 @@ void Power::power_off() { nextPowerCheck = now + 2500UL; if (is_power_needed()) power_on(); - else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) + else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn, SEC_TO_MS(POWER_TIMEOUT)))) power_off(); } } diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index 839366ca60..16f9dbcef5 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -24,8 +24,11 @@ /** * power.h - power control */ +#if PIN_EXISTS(PS_ON_EDM) || (PIN_EXISTS(PS_ON1_EDM) && ENABLED(PSU_OFF_REDUNDANT)) + #define PSU_TRACK_STATE_MS 1 +#endif -#if EITHER(AUTO_POWER_CONTROL, POWER_OFF_TIMER) +#if ANY(AUTO_POWER_CONTROL, POWER_OFF_TIMER, PSU_TRACK_STATE_MS) #include "../core/millis_t.h" #endif @@ -37,7 +40,11 @@ class Power { static void power_on(); static void power_off(); - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if PSU_TRACK_STATE_MS + static millis_t last_state_change_ms; + #endif + + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) #if ENABLED(POWER_OFF_TIMER) static millis_t power_off_time; static void setPowerOffTimer(const millis_t delay_ms); diff --git a/Marlin/src/feature/power_monitor.cpp b/Marlin/src/feature/power_monitor.cpp index 5a9db1ec24..e3c3e58fc4 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_lchar('A'); + lcd_put_u8str(F("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_lchar('V'); + lcd_put_u8str(F("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_lchar('W'); + lcd_put_u8str(F("W")); } #endif diff --git a/Marlin/src/feature/power_monitor.h b/Marlin/src/feature/power_monitor.h index fa06909053..d57ef6fa67 100644 --- a/Marlin/src/feature/power_monitor.h +++ b/Marlin/src/feature/power_monitor.h @@ -46,11 +46,11 @@ struct pm_lpf_t { class PowerMonitor { private: #if ENABLED(POWER_MONITOR_CURRENT) - static constexpr float amps_adc_scale = float(ADC_VREF) / (POWER_MONITOR_VOLTS_PER_AMP * PM_SAMPLE_RANGE); + static constexpr float amps_adc_scale = (float(ADC_VREF_MV) / 1000.0f) / (POWER_MONITOR_VOLTS_PER_AMP * PM_SAMPLE_RANGE); static pm_lpf_t amps; #endif #if ENABLED(POWER_MONITOR_VOLTAGE) - static constexpr float volts_adc_scale = float(ADC_VREF) / (POWER_MONITOR_VOLTS_PER_VOLT * PM_SAMPLE_RANGE); + static constexpr float volts_adc_scale = (float(ADC_VREF_MV) / 1000.0f) / (POWER_MONITOR_VOLTS_PER_VOLT * PM_SAMPLE_RANGE); static pm_lpf_t volts; #endif @@ -119,7 +119,7 @@ public: volts.reset(); #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA display_item_ms = 0; display_item = 0; #endif diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index d4450adcd8..0dd19808bc 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -28,20 +28,29 @@ #if ENABLED(POWER_LOSS_RECOVERY) +#include "../inc/MarlinConfig.h" + #include "powerloss.h" -#include "../core/macros.h" -bool PrintJobRecovery::enabled; // Initialized by settings.load() +#if ENABLED(EXTENSIBLE_UI) + #include "../lcd/extui/ui_api.h" +#endif -SdFile PrintJobRecovery::file; +bool PrintJobRecovery::enabled; // Initialized by settings.load + +#if HAS_PLR_BED_THRESHOLD + celsius_t PrintJobRecovery::bed_temp_threshold; // Initialized by settings.load +#endif + +MediaFile PrintJobRecovery::file; job_recovery_info_t PrintJobRecovery::info; const char PrintJobRecovery::filename[5] = "/PLR"; uint8_t PrintJobRecovery::queue_index_r; uint32_t PrintJobRecovery::cmd_sdpos, // = 0 PrintJobRecovery::sdpos[BUFSIZE]; -#if HAS_DWIN_E3V2_BASIC - bool PrintJobRecovery::dwin_flag; // = false +#if HAS_PLR_UI_FLAG + bool PrintJobRecovery::ui_flag_resume; // = false #endif #include "../sd/cardreader.h" @@ -52,12 +61,15 @@ uint32_t PrintJobRecovery::cmd_sdpos, // = 0 #include "../module/planner.h" #include "../module/printcounter.h" #include "../module/temperature.h" -#include "../core/serial.h" #if HOMING_Z_WITH_PROBE #include "../module/probe.h" #endif +#if ENABLED(SOVOL_SV06_RTS) + #include "../lcd/sovol_rts/sovol_rts.h" +#endif + #if ENABLED(FWRETRACT) #include "fwretract.h" #endif @@ -67,21 +79,27 @@ uint32_t PrintJobRecovery::cmd_sdpos, // = 0 PrintJobRecovery recovery; -#ifndef POWER_LOSS_PURGE_LEN - #define POWER_LOSS_PURGE_LEN 0 -#endif - #if DISABLED(BACKUP_POWER_SUPPLY) #undef POWER_LOSS_RETRACT_LEN // No retract at outage without backup power #endif #ifndef POWER_LOSS_RETRACT_LEN #define POWER_LOSS_RETRACT_LEN 0 #endif +#ifndef POWER_LOSS_PURGE_LEN + #define POWER_LOSS_PURGE_LEN 0 +#endif + +// Allow power-loss recovery to be aborted +#define PLR_CAN_ABORT +#define PROCESS_SUBCOMMANDS_NOW(cmd) do{ \ + if (TERN0(PLR_CAN_ABORT, card.flag.abort_sd_printing)) return; \ + gcode.process_subcommands_now(cmd); \ + }while(0) /** * Clear the recovery info */ -void PrintJobRecovery::init() { memset(&info, 0, sizeof(info)); } +void PrintJobRecovery::init() { info = { 0 }; } /** * Enable or disable then call changed() @@ -99,8 +117,9 @@ void PrintJobRecovery::enable(const bool onoff) { void PrintJobRecovery::changed() { if (!enabled) purge(); - else if (IS_SD_PRINTING()) + else if (card.isStillPrinting()) save(true); + TERN_(EXTENSIBLE_UI, ExtUI::onSetPowerLoss(enabled)); } /** @@ -122,6 +141,14 @@ bool PrintJobRecovery::check() { return success; } +/** + * Cancel recovery + */ +void PrintJobRecovery::cancel() { + TERN_(PLR_HEAT_BED_ON_REBOOT, set_bed_temp(false)); + purge(); +} + /** * Delete the recovery file and clear the recovery data */ @@ -155,7 +182,7 @@ void PrintJobRecovery::prepare() { */ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POWER_LOSS_ZRAISE*/, const bool raised/*=false*/) { - // We don't check IS_SD_PRINTING here so a save may occur during a pause + // We don't check isStillPrinting here so a save may occur during a pause #if SAVE_INFO_INTERVAL_MS > 0 static millis_t next_save_ms; // = 0 @@ -183,39 +210,43 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW // Set Head and Foot to matching non-zero values if (!++info.valid_head) ++info.valid_head; // non-zero in sequence - //if (!IS_SD_PRINTING()) info.valid_head = 0; + //if (!card.isStillPrinting()) info.valid_head = 0; info.valid_foot = info.valid_head; // Machine state // info.sdpos and info.current_position are pre-filled from the Stepper ISR info.feedrate = uint16_t(MMS_TO_MMM(feedrate_mm_s)); + info.feedrate_percentage = feedrate_percentage; + COPY(info.flow_percentage, planner.flow_percentage); + info.zraise = zraise; info.flag.raised = raised; // Was Z raised before power-off? + TERN_(CANCEL_OBJECTS, info.cancel_state = cancelable.state); TERN_(GCODE_REPEAT_MARKERS, info.stored_repeat = repeat); TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset); - TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift); + TERN_(HAS_WORKSPACE_OFFSET, info.workspace_offset = workspace_offset); E_TERN_(info.active_extruder = active_extruder); - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION info.flag.volumetric_enabled = parser.volumetric_enabled; #if HAS_MULTI_EXTRUDER - EXTRUDER_LOOP() info.filament_size[e] = planner.filament_size[e]; + COPY(info.filament_size, planner.filament_size); #else if (parser.volumetric_enabled) info.filament_size[0] = planner.filament_size[active_extruder]; #endif #endif - #if HAS_EXTRUDERS + #if HAS_HOTEND HOTEND_LOOP() info.target_temperature[e] = thermalManager.degTargetHotend(e); #endif TERN_(HAS_HEATED_BED, info.target_temperature_bed = thermalManager.degTargetBed()); - #if HAS_FAN - COPY(info.fan_speed, thermalManager.fan_speed); - #endif + TERN_(HAS_HEATED_CHAMBER, info.target_temperature_chamber = thermalManager.degTargetChamber()); + + TERN_(HAS_FAN, COPY(info.fan_speed, thermalManager.fan_speed)); #if HAS_LEVELING info.flag.leveling = planner.leveling_active; @@ -247,23 +278,23 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW #if ENABLED(BACKUP_POWER_SUPPLY) - void PrintJobRecovery::retract_and_lift(const_float_t zraise) { + void PrintJobRecovery::retract_and_lift(const float zraise) { #if POWER_LOSS_RETRACT_LEN || POWER_LOSS_ZRAISE gcode.set_relative_mode(true); // Use relative coordinates #if POWER_LOSS_RETRACT_LEN // Retract filament now - gcode.process_subcommands_now(F("G1 F3000 E-" STRINGIFY(POWER_LOSS_RETRACT_LEN))); + const uint16_t old_flow = planner.flow_percentage[active_extruder]; + planner.set_flow(active_extruder, 100); + gcode.process_subcommands_now(F("G1F3000E-" STRINGIFY(POWER_LOSS_RETRACT_LEN))); + planner.set_flow(active_extruder, old_flow); #endif #if POWER_LOSS_ZRAISE // Raise the Z axis now - if (zraise) { - char cmd[20], str_1[16]; - sprintf_P(cmd, PSTR("G0Z%s"), dtostrf(zraise, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); - } + if (zraise) + gcode.process_subcommands_now(TS(F("G0Z"), p_float_t(zraise, 3))); #else UNUSED(zraise); #endif @@ -290,7 +321,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW void PrintJobRecovery::_outage(TERN_(DEBUG_POWER_LOSS_RECOVERY, const bool simulated/*=false*/)) { #if ENABLED(BACKUP_POWER_SUPPLY) static bool lock = false; - if (lock) return; // No re-entrance from idle() during retract_and_lift() + if (lock) return; // No re-entrance from marlin.idle() during retract_and_lift() lock = true; #endif @@ -303,7 +334,10 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW // Save the current position, distance that Z was (or should be) raised, // and a flag whether the raise was already done here. - if (IS_SD_PRINTING()) save(true, zraise, ENABLED(BACKUP_POWER_SUPPLY)); + if (card.isStillPrinting()) save(true, zraise, ENABLED(BACKUP_POWER_SUPPLY)); + + // Tell the LCD about the outage, even though it is about to die + TERN_(EXTENSIBLE_UI, ExtUI::onPowerLoss()); // Disable all heaters to reduce power loss thermalManager.disable_all_heaters(); @@ -321,7 +355,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW sync_plan_position(); } else - kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY)); + marlin.kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY)); } #endif // POWER_LOSS_PIN || DEBUG_POWER_LOSS_RECOVERY @@ -340,33 +374,53 @@ void PrintJobRecovery::write() { if (!file.close()) DEBUG_ECHOLNPGM("Power-loss file close failed."); } +#if ENABLED(PLR_HEAT_BED_ON_REBOOT) + // Set bed temperature and wait. Called from M1000 to resume bed heating. + void PrintJobRecovery::set_bed_temp(const bool on) { + PROCESS_SUBCOMMANDS_NOW(TS(F("M190S"), on ? info.target_temperature_bed + PLR_HEAT_BED_EXTRA : 0)); + } +#endif + /** * Resume the saved print job */ void PrintJobRecovery::resume() { - - char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16]; - - const uint32_t resume_sdpos = info.sdpos; // Get here before the stepper ISR overwrites it + // Get these fields before any moves because stepper.cpp overwrites them + const xyze_pos_t resume_pos = info.current_position; + const uint32_t resume_sdpos = info.sdpos; // Apply the dry-run flag if enabled if (info.flag.dryrun) marlin_debug_flags |= MARLIN_DEBUG_DRYRUN; + #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) + struct OnExit { + uint8_t old_flags; + OnExit() { + old_flags = marlin_debug_flags; + marlin_debug_flags |= MARLIN_DEBUG_ECHO; + } + ~OnExit() { marlin_debug_flags = old_flags; } + } on_exit; + #endif + // Restore cold extrusion permission TERN_(PREVENT_COLD_EXTRUSION, thermalManager.allow_cold_extrude = info.flag.allow_cold_extrusion); #if HAS_LEVELING // Make sure leveling is off before any G92 and G28 - gcode.process_subcommands_now(F("M420 S0 Z0")); + PROCESS_SUBCOMMANDS_NOW(F("M420S0")); + #endif + + #if HAS_HEATED_CHAMBER + // Restore the chamber temperature + const celsius_t ct = info.target_temperature_chamber; + if (ct) PROCESS_SUBCOMMANDS_NOW(TS(F("M191S"), ct)); #endif #if HAS_HEATED_BED + // Restore the bed temperature const celsius_t bt = info.target_temperature_bed; - if (bt) { - // Restore the bed temperature - sprintf_P(cmd, PSTR("M190S%i"), bt); - gcode.process_subcommands_now(cmd); - } + if (bt) PROCESS_SUBCOMMANDS_NOW(TS(F("M190S"), bt)); #endif // Heat hotend enough to soften material @@ -374,37 +428,36 @@ void PrintJobRecovery::resume() { HOTEND_LOOP() { const celsius_t et = _MAX(info.target_temperature[e], 180); if (et) { - #if HAS_MULTI_HOTEND - sprintf_P(cmd, PSTR("T%iS"), e); - gcode.process_subcommands_now(cmd); - #endif - sprintf_P(cmd, PSTR("M109S%i"), et); - gcode.process_subcommands_now(cmd); + TERN_(HAS_MULTI_HOTEND, PROCESS_SUBCOMMANDS_NOW(TS('T', e, 'S'))); + PROCESS_SUBCOMMANDS_NOW(TS(F("M109S"), et)); } } #endif // Interpret the saved Z according to flags - const float z_print = info.current_position.z, - z_raised = z_print + info.zraise; + const float z_print = resume_pos.z; + + #if ANY(Z_HOME_TO_MAX, POWER_LOSS_RECOVER_ZHOME) || DISABLED(BELTPRINTER) + const float z_raised = z_print + info.zraise; + #endif // // Home the axes that can safely be homed, and // establish the current position as best we can. // - gcode.process_subcommands_now(F("G92.9E0")); // Reset E to 0 + PROCESS_SUBCOMMANDS_NOW(F("G92.9E0")); // Reset E to 0 #if Z_HOME_TO_MAX float z_now = z_raised; // If Z homing goes to max then just move back to the "raised" position - sprintf_P(cmd, PSTR( - "G28R0\n" // Home all axes (no raise) - "G1Z%sF1200" // Move Z down to (raised) height - ), dtostrf(z_now, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS( + F( "G28R0\n" // Home all axes (no raise) + "G1F1200Z") // Move Z down to (raised) height + , p_float_t(z_now, 3) + )); #elif DISABLED(BELTPRINTER) @@ -416,27 +469,24 @@ void PrintJobRecovery::resume() { #if !HOMING_Z_DOWN // Set Z to the real position - sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("G92.9Z"), p_float_t(z_now, 3))); #endif // Does Z need to be raised now? It should be raised before homing XY. if (z_raised > z_now) { z_now = z_raised; - sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("G1F600Z"), p_float_t(z_now, 3))); } // Home XY with no Z raise - gcode.process_subcommands_now(F("G28R0XY")); // No raise during G28 + PROCESS_SUBCOMMANDS_NOW(F("G28R0XY")); // No raise during G28 #endif #if HOMING_Z_DOWN // Move to a safe XY position and home Z while avoiding the print. const xy_pos_t p = xy_pos_t(POWER_LOSS_ZHOME_POS) TERN_(HOMING_Z_WITH_PROBE, - probe.offset_xy); - sprintf_P(cmd, PSTR("G1X%sY%sF1000\nG28HZ"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("G1F1000X"), p_float_t(p.x, 3), 'Y', p_float_t(p.y, 3), F("\nG28HZ"))); #endif // Mark all axes as having been homed (no effect on current_position) @@ -446,39 +496,30 @@ void PrintJobRecovery::resume() { // Restore Z fade and possibly re-enable bed leveling compensation. // Leveling may already be enabled due to the ENABLE_LEVELING_AFTER_G28 option. // TODO: Add a G28 parameter to leave leveling disabled. - sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("M420S"), '0' + (char)info.flag.leveling, 'Z', p_float_t(info.fade, 1))); #if !HOMING_Z_DOWN // The physical Z was adjusted at power-off so undo the M420S1 correction to Z with G92.9. - sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 1, str_1)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("G92.9Z"), p_float_t(z_now, 3))); #endif #endif #if ENABLED(POWER_LOSS_RECOVER_ZHOME) // Z was homed down to the bed, so move up to the raised height. z_now = z_raised; - sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("G1F600Z"), p_float_t(z_now, 3))); #endif // Recover volumetric extrusion state - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION #if HAS_MULTI_EXTRUDER - EXTRUDER_LOOP() { - sprintf_P(cmd, PSTR("M200T%iD%s"), e, dtostrf(info.filament_size[e], 1, 3, str_1)); - gcode.process_subcommands_now(cmd); - } - if (!info.flag.volumetric_enabled) { - sprintf_P(cmd, PSTR("M200T%iD0"), info.active_extruder); - gcode.process_subcommands_now(cmd); - } + EXTRUDER_LOOP() + PROCESS_SUBCOMMANDS_NOW(TS(F("M200T"), e, F("D"), p_float_t(info.filament_size[e], 3))); + if (!info.flag.volumetric_enabled) + PROCESS_SUBCOMMANDS_NOW(TS(F("M200D0T"), info.active_extruder)); #else - if (info.flag.volumetric_enabled) { - sprintf_P(cmd, PSTR("M200D%s"), dtostrf(info.filament_size[0], 1, 3, str_1)); - gcode.process_subcommands_now(cmd); - } + if (info.flag.volumetric_enabled) + PROCESS_SUBCOMMANDS_NOW(TS(F("M200D"), p_float_t(info.filament_size[0], 3))); #endif #endif @@ -487,34 +528,26 @@ void PrintJobRecovery::resume() { HOTEND_LOOP() { const celsius_t et = info.target_temperature[e]; if (et) { - #if HAS_MULTI_HOTEND - sprintf_P(cmd, PSTR("T%iS"), e); - gcode.process_subcommands_now(cmd); - #endif - sprintf_P(cmd, PSTR("M109S%i"), et); - gcode.process_subcommands_now(cmd); + TERN_(HAS_MULTI_HOTEND, PROCESS_SUBCOMMANDS_NOW(TS('T', e, 'S'))); + PROCESS_SUBCOMMANDS_NOW(TS(F("M109S"), et)); } } #endif // Restore the previously active tool (with no_move) #if HAS_MULTI_EXTRUDER || HAS_MULTI_HOTEND - sprintf_P(cmd, PSTR("T%i S"), info.active_extruder); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS('T', info.active_extruder, 'S')); #endif // Restore print cooling fan speeds #if HAS_FAN FANS_LOOP(i) { const int f = info.fan_speed[i]; - if (f) { - sprintf_P(cmd, PSTR("M106P%iS%i"), i, f); - gcode.process_subcommands_now(cmd); - } + if (f) PROCESS_SUBCOMMANDS_NOW(TS(F("M106P"), i, 'S', f)); } #endif - // Restore retract and hop state from an active `G10` command + // Restore retract and hop state from an active 'G10' command #if ENABLED(FWRETRACT) EXTRUDER_LOOP() { if (info.retract[e] != 0.0) { @@ -531,104 +564,108 @@ void PrintJobRecovery::resume() { // Un-retract if there was a retract at outage #if ENABLED(BACKUP_POWER_SUPPLY) && POWER_LOSS_RETRACT_LEN > 0 - gcode.process_subcommands_now(F("G1F3000E" STRINGIFY(POWER_LOSS_RETRACT_LEN))); + PROCESS_SUBCOMMANDS_NOW(F("G1F3000E" STRINGIFY(POWER_LOSS_RETRACT_LEN))); #endif // Additional purge on resume if configured #if POWER_LOSS_PURGE_LEN - sprintf_P(cmd, PSTR("G1F3000E%d"), (POWER_LOSS_PURGE_LEN) + (POWER_LOSS_RETRACT_LEN)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("G1F3000E"), (POWER_LOSS_PURGE_LEN) + (POWER_LOSS_RETRACT_LEN))); #endif #if ENABLED(NOZZLE_CLEAN_FEATURE) - gcode.process_subcommands_now(F("G12")); + PROCESS_SUBCOMMANDS_NOW(F("G12")); #endif // Move back over to the saved XY - sprintf_P(cmd, PSTR("G1X%sY%sF3000"), - dtostrf(info.current_position.x, 1, 3, str_1), - dtostrf(info.current_position.y, 1, 3, str_2) - ); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS( + F("G1F3000X"), p_float_t(resume_pos.x, 3), 'Y', p_float_t(resume_pos.y, 3) + )); // Move back down to the saved Z for printing - sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_print, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("G1F600Z"), p_float_t(z_print, 3))); - // Restore the feedrate - sprintf_P(cmd, PSTR("G1F%d"), info.feedrate); - gcode.process_subcommands_now(cmd); + // Restore the feedrate and percentage + PROCESS_SUBCOMMANDS_NOW(TS(F("G1F"), info.feedrate)); + feedrate_percentage = info.feedrate_percentage; + + // Flowrate percentage + EXTRUDER_LOOP() planner.set_flow(e, info.flow_percentage[e]); // Restore E position with G92.9 - sprintf_P(cmd, PSTR("G92.9E%s"), dtostrf(info.current_position.e, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(TS(F("G92.9E"), p_float_t(resume_pos.e, 3))); + + #if ENABLED(CANCEL_OBJECTS) + cancelable.state = info.cancel_state; + cancelable.set_active_object(); // Sets the status message + #endif TERN_(GCODE_REPEAT_MARKERS, repeat = info.stored_repeat); TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset); - TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift); - #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT - LOOP_NUM_AXES(i) update_workspace_offset((AxisEnum)i); - #endif + TERN_(HAS_WORKSPACE_OFFSET, workspace_offset = info.workspace_offset); // Relative axis modes gcode.axis_relative = info.axis_relative; - #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) - const uint8_t old_flags = marlin_debug_flags; - marlin_debug_flags |= MARLIN_DEBUG_ECHO; - #endif - // Continue to apply PLR when a file is resumed! enable(true); // Resume the SD file from the last position - char *fn = info.sd_filename; - sprintf_P(cmd, M23_STR, fn); - gcode.process_subcommands_now(cmd); - sprintf_P(cmd, PSTR("M24S%ldT%ld"), resume_sdpos, info.print_job_elapsed); - gcode.process_subcommands_now(cmd); + PROCESS_SUBCOMMANDS_NOW(MString(F("M23 "), info.sd_filename)); + PROCESS_SUBCOMMANDS_NOW(TS(F("M24S"), resume_sdpos, 'T', info.print_job_elapsed)); - TERN_(DEBUG_POWER_LOSS_RECOVERY, marlin_debug_flags = old_flags); + #if ENABLED(SOVOL_SV06_RTS) + if (rts.print_state) rts.refreshTime(); + rts.start_print_flag = false; + #endif } #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) void PrintJobRecovery::debug(FSTR_P const prefix) { - DEBUG_ECHOF(prefix); - DEBUG_ECHOLNPGM(" Job Recovery Info...\nvalid_head:", info.valid_head, " valid_foot:", info.valid_foot); + DEBUG_ECHOLN(prefix, F(" Job Recovery Info...\nvalid_head:"), info.valid_head, F(" valid_foot:"), info.valid_foot); if (info.valid_head) { if (info.valid_head == info.valid_foot) { DEBUG_ECHOPGM("current_position: "); LOOP_LOGICAL_AXES(i) { if (i) DEBUG_CHAR(','); - DEBUG_DECIMAL(info.current_position[i]); + DEBUG_ECHO(info.current_position[i]); } DEBUG_EOL(); - DEBUG_ECHOLNPGM("feedrate: ", info.feedrate); + DEBUG_ECHOLN(F("feedrate: "), info.feedrate, F(" x "), info.feedrate_percentage, '%'); + EXTRUDER_LOOP() DEBUG_ECHOLN('E', e + 1, F(" flow %: "), info.flow_percentage[e]); DEBUG_ECHOLNPGM("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : ""); + #if ENABLED(CANCEL_OBJECTS) + const cancel_state_t cs = info.cancel_state; + DEBUG_ECHOPGM("Canceled:"); + for (int i = 0; i < cs.object_count; i++) + if (TEST(cs.canceled, i)) { DEBUG_CHAR(' '); DEBUG_ECHO(i); } + DEBUG_EOL(); + #endif + #if ENABLED(GCODE_REPEAT_MARKERS) - DEBUG_ECHOLNPGM("repeat index: ", info.stored_repeat.index); - LOOP_L_N(i, info.stored_repeat.index) - DEBUG_ECHOLNPGM("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter); + const uint8_t ind = info.stored_repeat.count(); + DEBUG_ECHOLNPGM("repeat markers: ", ind); + for (uint8_t i = ind; i--;) + DEBUG_ECHOLNPGM("...", i, " sdpos: ", info.stored_repeat.get_marker_sdpos(i), " count: ", info.stored_repeat.get_marker_counter(i)); #endif #if HAS_HOME_OFFSET DEBUG_ECHOPGM("home_offset: "); LOOP_NUM_AXES(i) { if (i) DEBUG_CHAR(','); - DEBUG_DECIMAL(info.home_offset[i]); + DEBUG_ECHO(info.home_offset[i]); } DEBUG_EOL(); #endif - #if HAS_POSITION_SHIFT - DEBUG_ECHOPGM("position_shift: "); + #if HAS_WORKSPACE_OFFSET + DEBUG_ECHOPGM("workspace_offset: "); LOOP_NUM_AXES(i) { if (i) DEBUG_CHAR(','); - DEBUG_DECIMAL(info.position_shift[i]); + DEBUG_ECHO(info.workspace_offset[i]); } DEBUG_EOL(); #endif @@ -637,7 +674,7 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPGM("active_extruder: ", info.active_extruder); #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION DEBUG_ECHOPGM("filament_size:"); EXTRUDER_LOOP() DEBUG_ECHOLNPGM(" ", info.filament_size[e]); DEBUG_EOL(); @@ -656,6 +693,10 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPGM("target_temperature_bed: ", info.target_temperature_bed); #endif + #if HAS_HEATED_CHAMBER + DEBUG_ECHOLNPGM("target_temperature_chamber: ", info.target_temperature_chamber); + #endif + #if HAS_FAN DEBUG_ECHOPGM("fan_speed: "); FANS_LOOP(i) { @@ -680,7 +721,7 @@ void PrintJobRecovery::resume() { #endif // Mixing extruder and gradient - #if BOTH(MIXING_EXTRUDER, GRADIENT_MIX) + #if ALL(MIXING_EXTRUDER, GRADIENT_MIX) DEBUG_ECHOLNPGM("gradient: ", info.gradient.enabled ? "ON" : "OFF"); #endif @@ -699,7 +740,9 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPGM("flag.dryrun: ", AS_DIGIT(info.flag.dryrun)); DEBUG_ECHOLNPGM("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion)); - DEBUG_ECHOLNPGM("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); + #if HAS_VOLUMETRIC_EXTRUSION + DEBUG_ECHOLNPGM("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); + #endif } else DEBUG_ECHOLNPGM("INVALID DATA"); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 33d9dc007c..bfa5b4717f 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -30,20 +30,27 @@ #include "../inc/MarlinConfig.h" +#if ENABLED(CANCEL_OBJECTS) + #include "cancel_object.h" +#endif + #if ENABLED(GCODE_REPEAT_MARKERS) - #include "../feature/repeat.h" + #include "repeat.h" #endif #if ENABLED(MIXING_EXTRUDER) - #include "../feature/mixing.h" + #include "mixing.h" #endif #if !defined(POWER_LOSS_STATE) && PIN_EXISTS(POWER_LOSS) #define POWER_LOSS_STATE HIGH #endif +#if DISABLED(BACKUP_POWER_SUPPLY) + #undef POWER_LOSS_ZRAISE // No Z raise at outage without backup power +#endif #ifndef POWER_LOSS_ZRAISE - #define POWER_LOSS_ZRAISE 2 + #define POWER_LOSS_ZRAISE 2 // Default Z-raise on outage or resume #endif //#define DEBUG_POWER_LOSS_RECOVERY @@ -56,9 +63,16 @@ typedef struct { // Machine state xyze_pos_t current_position; uint16_t feedrate; + int16_t feedrate_percentage; + uint16_t flow_percentage[EXTRUDERS]; float zraise; + // Canceled objects + #if ENABLED(CANCEL_OBJECTS) + cancel_state_t cancel_state; + #endif + // Repeat information #if ENABLED(GCODE_REPEAT_MARKERS) Repeat stored_repeat; @@ -67,14 +81,14 @@ typedef struct { #if HAS_HOME_OFFSET xyz_pos_t home_offset; #endif - #if HAS_POSITION_SHIFT - xyz_pos_t position_shift; + #if HAS_WORKSPACE_OFFSET + xyz_pos_t workspace_offset; #endif #if HAS_MULTI_EXTRUDER uint8_t active_extruder; #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION float filament_size[EXTRUDERS]; #endif @@ -84,6 +98,9 @@ typedef struct { #if HAS_HEATED_BED celsius_t target_temperature_bed; #endif + #if HAS_HEATED_CHAMBER + celsius_t target_temperature_chamber; + #endif #if HAS_FAN uint8_t fan_speed[FAN_COUNT]; #endif @@ -113,7 +130,7 @@ typedef struct { millis_t print_job_elapsed; // Relative axis modes - uint8_t axis_relative; + relative_t axis_relative; // Misc. Marlin flags struct { @@ -123,7 +140,7 @@ typedef struct { #if HAS_LEVELING bool leveling:1; // M420 S #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION bool volumetric_enabled:1; // M200 S D #endif } flag; @@ -138,21 +155,24 @@ class PrintJobRecovery { public: static const char filename[5]; - static SdFile file; + static MediaFile file; static job_recovery_info_t info; static uint8_t queue_index_r; //!< Queue index of the active command static uint32_t cmd_sdpos, //!< SD position of the next command sdpos[BUFSIZE]; //!< SD positions of queued commands - #if HAS_DWIN_E3V2_BASIC - static bool dwin_flag; + #if HAS_PLR_UI_FLAG + static bool ui_flag_resume; //!< Flag the UI to show a dialog to Resume (M1000) or Cancel (M1000C) #endif static void init(); static void prepare(); static void setup() { + #if PIN_EXISTS(OUTAGECON) + OUT_WRITE(OUTAGECON_PIN, HIGH); + #endif #if PIN_EXISTS(POWER_LOSS) #if ENABLED(POWER_LOSS_PULLUP) SET_INPUT_PULLUP(POWER_LOSS_PIN); @@ -172,15 +192,24 @@ class PrintJobRecovery { static void enable(const bool onoff); static void changed(); + #if HAS_PLR_BED_THRESHOLD + static celsius_t bed_temp_threshold; + #endif + static bool exists() { return card.jobRecoverFileExists(); } static void open(const bool read) { card.openJobRecoveryFile(read); } static void close() { file.close(); } static bool check(); + + #if ENABLED(PLR_HEAT_BED_ON_REBOOT) + static void set_bed_temp(const bool turn_on); + #endif + static void resume(); static void purge(); - static void cancel() { purge(); } + static void cancel(); static void load(); static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=POWER_LOSS_ZRAISE, const bool raised=false); @@ -213,7 +242,7 @@ class PrintJobRecovery { static void write(); #if ENABLED(BACKUP_POWER_SUPPLY) - static void retract_and_lift(const_float_t zraise); + static void retract_and_lift(const float zraise); #endif #if PIN_EXISTS(POWER_LOSS) || ENABLED(DEBUG_POWER_LOSS_RECOVERY) diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index b5f636e698..7dfa28f4b9 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -66,13 +66,13 @@ float ProbeTempComp::init_measurement; // = 0.0 bool ProbeTempComp::enabled = true; void ProbeTempComp::reset() { - TERN_(PTC_PROBE, LOOP_L_N(i, PTC_PROBE_COUNT) z_offsets_probe[i] = z_offsets_probe_default[i]); - TERN_(PTC_BED, LOOP_L_N(i, PTC_BED_COUNT) z_offsets_bed[i] = z_offsets_bed_default[i]); - TERN_(PTC_HOTEND, LOOP_L_N(i, PTC_HOTEND_COUNT) z_offsets_hotend[i] = z_offsets_hotend_default[i]); + TERN_(PTC_PROBE, for (uint8_t i = 0; i < PTC_PROBE_COUNT; ++i) z_offsets_probe[i] = z_offsets_probe_default[i]); + TERN_(PTC_BED, for (uint8_t i = 0; i < PTC_BED_COUNT; ++i) z_offsets_bed[i] = z_offsets_bed_default[i]); + TERN_(PTC_HOTEND, for (uint8_t i = 0; i < PTC_HOTEND_COUNT; ++i) z_offsets_hotend[i] = z_offsets_hotend_default[i]); } void ProbeTempComp::clear_offsets(const TempSensorID tsi) { - LOOP_L_N(i, cali_info[tsi].measurements) + for (uint8_t i = 0; i < cali_info[tsi].measurements; ++i) sensor_z_offsets[tsi][i] = 0; calib_idx = 0; } @@ -84,17 +84,12 @@ bool ProbeTempComp::set_offset(const TempSensorID tsi, const uint8_t idx, const } void ProbeTempComp::print_offsets() { - LOOP_L_N(s, TSI_COUNT) { + for (uint8_t s = 0; s < TSI_COUNT; ++s) { celsius_t temp = cali_info[s].start_temp; for (int16_t i = -1; i < cali_info[s].measurements; ++i) { - SERIAL_ECHOF( - TERN_(PTC_BED, s == TSI_BED ? F("Bed") :) - TERN_(PTC_HOTEND, s == TSI_EXT ? F("Extruder") :) - F("Probe") - ); - SERIAL_ECHOLNPGM( - " temp: ", temp, - "C; Offset: ", i < 0 ? 0.0f : sensor_z_offsets[s][i], " um" + SERIAL_ECHOLN( + TERN_(PTC_BED, s == TSI_BED ? F("Bed") :) TERN_(PTC_HOTEND, s == TSI_EXT ? F("Extruder") :) F("Probe"), + F(" temp: "), temp, F("C; Offset: "), i < 0 ? 0.0f : sensor_z_offsets[s][i], F(" um") ); temp += cali_info[s].temp_resolution; } @@ -109,12 +104,12 @@ void ProbeTempComp::print_offsets() { #endif } -void ProbeTempComp::prepare_new_calibration(const_float_t init_meas_z) { +void ProbeTempComp::prepare_new_calibration(const float init_meas_z) { calib_idx = 0; init_measurement = init_meas_z; } -void ProbeTempComp::push_back_new_measurement(const TempSensorID tsi, const_float_t meas_z) { +void ProbeTempComp::push_back_new_measurement(const TempSensorID tsi, const float meas_z) { if (calib_idx >= cali_info[tsi].measurements) return; sensor_z_offsets[tsi][calib_idx++] = static_cast((meas_z - init_measurement) * 1000.0f); } @@ -191,7 +186,7 @@ void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius }; // Interpolate Z based on a temperature being within a given range - auto linear_interp = [](const_float_t x, xy_float_t p1, xy_float_t p2) { + auto linear_interp = [](const float x, xy_float_t p1, xy_float_t p2) { // zoffs1 + zoffset_per_toffset * toffset return p1.y + (p2.y - p1.y) / (p2.x - p1.x) * (x - p1.x); }; @@ -217,7 +212,7 @@ void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius } // convert offset to mm and apply it - meas_z -= offset / 1000.0f; + meas_z -= offset * 0.001f; } bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d) { @@ -232,7 +227,7 @@ bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d sum_xy = 0, sum_y = 0; float xi = static_cast(start_temp); - LOOP_L_N(i, calib_idx) { + for (uint8_t i = 0; i < calib_idx; ++i) { const float yi = static_cast(data[i]); xi += res_temp; sum_x += xi; diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 42348db684..e6509a20cf 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -84,8 +84,8 @@ class ProbeTempComp { } static bool set_offset(const TempSensorID tsi, const uint8_t idx, const int16_t offset); static void print_offsets(); - static void prepare_new_calibration(const_float_t init_meas_z); - static void push_back_new_measurement(const TempSensorID tsi, const_float_t meas_z); + static void prepare_new_calibration(const float init_meas_z); + static void push_back_new_measurement(const TempSensorID tsi, const float meas_z); static bool finish_calibration(const TempSensorID tsi); static void set_enabled(const bool ena) { enabled = ena; } diff --git a/Marlin/src/feature/repeat.cpp b/Marlin/src/feature/repeat.cpp index 165f71fd0f..4484dab95b 100644 --- a/Marlin/src/feature/repeat.cpp +++ b/Marlin/src/feature/repeat.cpp @@ -42,7 +42,7 @@ void Repeat::add_marker(const uint32_t sdpos, const uint16_t count) { SERIAL_ECHO_MSG("!Too many markers."); else { marker[index].sdpos = sdpos; - marker[index].counter = count ?: -1; + marker[index].counter = count ? count - 1 : -1; index++; DEBUG_ECHOLNPGM("Add Marker ", index, " at ", sdpos, " (", count, ")"); } @@ -66,7 +66,7 @@ void Repeat::loop() { } } -void Repeat::cancel() { LOOP_L_N(i, index) marker[i].counter = 0; } +void Repeat::cancel() { for (uint8_t i = 0; i < index; ++i) marker[i].counter = 0; } void Repeat::early_parse_M808(char * const cmd) { if (is_command_M808(cmd)) { diff --git a/Marlin/src/feature/repeat.h b/Marlin/src/feature/repeat.h index fc11e4a9e2..ce309f6470 100644 --- a/Marlin/src/feature/repeat.h +++ b/Marlin/src/feature/repeat.h @@ -40,7 +40,7 @@ private: public: static void reset() { index = 0; } static bool is_active() { - LOOP_L_N(i, index) if (marker[i].counter) return true; + for (uint8_t i = 0; i < index; ++i) if (marker[i].counter) return true; return false; } static bool is_command_M808(char * const cmd) { return cmd[0] == 'M' && cmd[1] == '8' && cmd[2] == '0' && cmd[3] == '8' && !NUMERIC(cmd[4]); } @@ -48,6 +48,9 @@ public: static void add_marker(const uint32_t sdpos, const uint16_t count); static void loop(); static void cancel(); + static uint8_t count() { return index; } + static int16_t get_marker_counter(const uint8_t i) { return marker[i].counter; } + static uint32_t get_marker_sdpos(const uint8_t i) { return marker[i].sdpos; } }; extern Repeat repeat; diff --git a/Marlin/src/feature/rs485.cpp b/Marlin/src/feature/rs485.cpp new file mode 100644 index 0000000000..8009185450 --- /dev/null +++ b/Marlin/src/feature/rs485.cpp @@ -0,0 +1,39 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../inc/MarlinConfig.h" + +#if HAS_RS485_SERIAL + +#include "rs485.h" + +HardwareSerialBusIO rs485BusIO(&RS485_SERIAL); +RS485Bus rs485Bus(rs485BusIO, RS485_RX_ENABLE_PIN, RS485_TX_ENABLE_PIN); + +PhotonProtocol rs485Protocol; + +Packetizer rs485Packetizer(rs485Bus, rs485Protocol); + +uint8_t rs485Buffer[RS485_SEND_BUFFER_SIZE]; + +void rs485_init() { RS485_SERIAL.begin(57600); } + +#endif // HAS_RS485_SERIAL diff --git a/Marlin/src/feature/rs485.h b/Marlin/src/feature/rs485.h new file mode 100644 index 0000000000..3327626a3c --- /dev/null +++ b/Marlin/src/feature/rs485.h @@ -0,0 +1,40 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../inc/MarlinConfigPre.h" + +#include +#include + +#include +#include + +#define RS485_SEND_BUFFER_SIZE 32 + +extern HardwareSerialBusIO rs485BusIO; +extern RS485Bus rs485Bus; +extern PhotonProtocol rs485Protocol; +extern Packetizer rs485Packetizer; +extern uint8_t rs485Buffer[RS485_SEND_BUFFER_SIZE]; + +void rs485_init(); diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index 98b6bd0510..f0b94d0de8 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -33,7 +33,7 @@ FilamentMonitor runout; bool FilamentMonitorBase::enabled = true, - FilamentMonitorBase::filament_ran_out; // = false + FilamentMonitorBase::filament_ran_out; // = false #if ENABLED(HOST_ACTION_COMMANDS) bool FilamentMonitorBase::host_handling; // = false @@ -47,10 +47,14 @@ bool FilamentMonitorBase::enabled = true, #if HAS_FILAMENT_RUNOUT_DISTANCE float RunoutResponseDelayed::runout_distance_mm = FILAMENT_RUNOUT_DISTANCE_MM; - volatile float RunoutResponseDelayed::runout_mm_countdown[NUM_RUNOUT_SENSORS]; + countdown_t RunoutResponseDelayed::mm_countdown; #if ENABLED(FILAMENT_MOTION_SENSOR) uint8_t FilamentSensorEncoder::motion_detected; #endif + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + bool RunoutResponseDelayed::ignore_motion = false; + float RunoutResponseDelayed::motion_distance_mm = FILAMENT_MOTION_DISTANCE_MM; + #endif #else int8_t RunoutResponseDebounced::runout_count[NUM_RUNOUT_SENSORS]; // = 0 #endif @@ -59,7 +63,7 @@ bool FilamentMonitorBase::enabled = true, // Filament Runout event handler // #include "../MarlinCore.h" -#include "../feature/pause.h" +#include "pause.h" #include "../gcode/queue.h" #if ENABLED(HOST_ACTION_COMMANDS) @@ -68,12 +72,12 @@ bool FilamentMonitorBase::enabled = true, #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_LCD_PROUI) - #include "../lcd/e3v2/proui/dwin.h" #endif void event_filament_runout(const uint8_t extruder) { + runout.init_for_restart(false); // Reset and disable + if (did_pause_print) return; // Action already in progress. Purge triggered repeated runout. #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) @@ -88,7 +92,6 @@ void event_filament_runout(const uint8_t extruder) { #endif TERN_(EXTENSIBLE_UI, ExtUI::onFilamentRunout(ExtUI::getTool(extruder))); - TERN_(DWIN_LCD_PROUI, DWIN_FilamentRunout(extruder)); #if ANY(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS, MULTI_FILAMENT_SENSOR) const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, extruder); @@ -102,12 +105,16 @@ void event_filament_runout(const uint8_t extruder) { const bool run_runout_script = !runout.host_handling; #if ENABLED(HOST_ACTION_COMMANDS) - if (run_runout_script - && ( strstr(FILAMENT_RUNOUT_SCRIPT, "M600") + + const bool park_or_pause = (false + #ifdef FILAMENT_RUNOUT_SCRIPT + || strstr(FILAMENT_RUNOUT_SCRIPT, "M600") || strstr(FILAMENT_RUNOUT_SCRIPT, "M125") || TERN0(ADVANCED_PAUSE_FEATURE, strstr(FILAMENT_RUNOUT_SCRIPT, "M25")) - ) - ) { + #endif + ); + + if (run_runout_script && park_or_pause) { hostui.paused(false); } else { @@ -124,24 +131,27 @@ void event_filament_runout(const uint8_t extruder) { SERIAL_ECHOPGM(" " ACTION_REASON_ON_FILAMENT_RUNOUT " "); SERIAL_CHAR(tool); SERIAL_EOL(); + #endif // HOST_ACTION_COMMANDS - if (run_runout_script) { - #if MULTI_FILAMENT_SENSOR - char script[strlen(FILAMENT_RUNOUT_SCRIPT) + 1]; - sprintf_P(script, PSTR(FILAMENT_RUNOUT_SCRIPT), tool); - #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) - SERIAL_ECHOLNPGM("Runout Command: ", script); + #ifdef FILAMENT_RUNOUT_SCRIPT + if (run_runout_script) { + #if MULTI_FILAMENT_SENSOR + MString script; + script.setf(F(FILAMENT_RUNOUT_SCRIPT), C(tool)); + #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) + SERIAL_ECHOLNPGM("Runout Command: ", &script); + #endif + queue.inject(&script); + #else + #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) + SERIAL_ECHOPGM("Runout Command: "); + SERIAL_ECHOLNPGM(FILAMENT_RUNOUT_SCRIPT); + #endif + queue.inject(F(FILAMENT_RUNOUT_SCRIPT)); #endif - queue.inject(script); - #else - #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) - SERIAL_ECHOPGM("Runout Command: "); - SERIAL_ECHOLNPGM(FILAMENT_RUNOUT_SCRIPT); - #endif - queue.inject(F(FILAMENT_RUNOUT_SCRIPT)); - #endif - } + } + #endif } #endif // HAS_FILAMENT_SENSOR diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index e74d857a79..7881af4e38 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -30,7 +30,7 @@ #include "../module/planner.h" #include "../module/stepper.h" // for block_t #include "../gcode/queue.h" -#include "../feature/pause.h" +#include "pause.h" // for did_pause_print #include "../inc/MarlinConfig.h" @@ -43,12 +43,31 @@ #define FILAMENT_RUNOUT_THRESHOLD 5 #endif +#if ENABLED(FILAMENT_MOTION_SENSOR) + #define HAS_FILAMENT_MOTION 1 + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + #define HAS_FILAMENT_SWITCH 1 + #endif +#else + #define HAS_FILAMENT_SWITCH 1 +#endif + +#define FILAMENT_IS_OUT(N...) (READ(FIL_RUNOUT##N##_PIN) == FIL_RUNOUT##N##_STATE) + +typedef Flags< + #if NUM_MOTION_SENSORS > NUM_RUNOUT_SENSORS + NUM_MOTION_SENSORS + #else + NUM_RUNOUT_SENSORS + #endif + > runout_flags_t; + void event_filament_runout(const uint8_t extruder); +inline bool should_monitor_runout() { return did_pause_print || marlin.printingIsActive(); } template class TFilamentMonitor; -class FilamentSensorEncoder; -class FilamentSensorSwitch; +class FilamentSensor; class RunoutResponseDelayed; class RunoutResponseDebounced; @@ -56,7 +75,7 @@ class RunoutResponseDebounced; typedef TFilamentMonitor< TERN(HAS_FILAMENT_RUNOUT_DISTANCE, RunoutResponseDelayed, RunoutResponseDebounced), - TERN(FILAMENT_MOTION_SENSOR, FilamentSensorEncoder, FilamentSensorSwitch) + FilamentSensor > FilamentMonitor; extern FilamentMonitor runout; @@ -98,14 +117,22 @@ class TFilamentMonitor : public FilamentMonitorBase { static void filament_present(const uint8_t extruder) { response.filament_present(extruder); } + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + static void filament_motion_present(const uint8_t extruder) { + response.filament_motion_present(extruder); + } + static float& motion_distance() { return response.motion_distance_mm; } + static void set_motion_distance(const float mm) { response.motion_distance_mm = mm; } + #endif #if HAS_FILAMENT_RUNOUT_DISTANCE static float& runout_distance() { return response.runout_distance_mm; } - static void set_runout_distance(const_float_t mm) { response.runout_distance_mm = mm; } + static void set_runout_distance(const float mm) { response.runout_distance_mm = mm; } #endif // Handle a block completion. RunoutResponseDelayed uses this to // add up the length of filament moved while the filament is out. + // Called from ISR context! static void block_completed(const block_t * const b) { if (enabled) { response.block_completed(b); @@ -115,49 +142,44 @@ class TFilamentMonitor : public FilamentMonitorBase { // Give the response a chance to update its counter. static void run() { - if (enabled && !filament_ran_out && (printingIsActive() || did_pause_print)) { - TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here - response.run(); - sensor.run(); - const uint8_t runout_flags = response.has_run_out(); - TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, sei()); - #if MULTI_FILAMENT_SENSOR - #if ENABLED(WATCH_ALL_RUNOUT_SENSORS) - const bool ran_out = !!runout_flags; // any sensor triggers - uint8_t extruder = 0; - if (ran_out) { - uint8_t bitmask = runout_flags; - while (!(bitmask & 1)) { - bitmask >>= 1; - extruder++; - } - } - #else - const bool ran_out = TEST(runout_flags, active_extruder); // suppress non active extruders - uint8_t extruder = active_extruder; - #endif + if (!enabled || filament_ran_out || !should_monitor_runout()) return; + TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here + response.run(); + sensor.run(); + const runout_flags_t runout_flags = response.has_run_out(); + TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, sei()); + #if MULTI_FILAMENT_SENSOR + #if ENABLED(WATCH_ALL_RUNOUT_SENSORS) + const bool ran_out = bool(runout_flags); // any sensor triggers + uint8_t extruder = 0; + if (ran_out) while (!runout_flags.test(extruder)) extruder++; #else - const bool ran_out = !!runout_flags; + const bool ran_out = runout_flags[active_extruder]; // suppress non active extruders uint8_t extruder = active_extruder; #endif + #else + const bool ran_out = bool(runout_flags); + uint8_t extruder = active_extruder; + #endif - #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) - if (runout_flags) { - SERIAL_ECHOPGM("Runout Sensors: "); - LOOP_L_N(i, 8) SERIAL_ECHO('0' + TEST(runout_flags, i)); - SERIAL_ECHOPGM(" -> ", extruder); - if (ran_out) SERIAL_ECHOPGM(" RUN OUT"); - SERIAL_EOL(); - } - #endif + if (!ran_out) return; - if (ran_out) { - filament_ran_out = true; - event_filament_runout(extruder); - planner.synchronize(); - } - } + #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) + SERIAL_ECHOPGM("Runout Sensors: "); + for (uint8_t i = 0; i < 8; ++i) SERIAL_CHAR('0' + char(runout_flags[i])); + SERIAL_ECHOLNPGM(" -> ", extruder, " RUN OUT"); + #endif + + filament_ran_out = true; + event_filament_runout(extruder); + planner.synchronize(); } + + // Reset after a filament runout or upon resuming a job + static void init_for_restart(const bool onoff=true) { + response.init_for_restart(onoff); + } + }; /*************************** FILAMENT PRESENCE SENSORS ***************************/ @@ -171,37 +193,25 @@ class FilamentSensorBase { static void filament_present(const uint8_t extruder) { runout.filament_present(extruder); // ...which calls response.filament_present(extruder) } + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + static void filament_motion_present(const uint8_t extruder) { + runout.filament_motion_present(extruder); // ...which calls response.filament_motion_present(extruder) + } + #endif public: static void setup() { - #define _INIT_RUNOUT_PIN(P,S,U,D) do{ if (ENABLED(U)) SET_INPUT_PULLUP(P); else if (ENABLED(D)) SET_INPUT_PULLDOWN(P); else SET_INPUT(P); }while(0) - #define INIT_RUNOUT_PIN(N) _INIT_RUNOUT_PIN(FIL_RUNOUT##N##_PIN, FIL_RUNOUT##N##_STATE, FIL_RUNOUT##N##_PULLUP, FIL_RUNOUT##N##_PULLDOWN) - #if NUM_RUNOUT_SENSORS >= 1 - INIT_RUNOUT_PIN(1); - #endif - #if NUM_RUNOUT_SENSORS >= 2 - INIT_RUNOUT_PIN(2); - #endif - #if NUM_RUNOUT_SENSORS >= 3 - INIT_RUNOUT_PIN(3); - #endif - #if NUM_RUNOUT_SENSORS >= 4 - INIT_RUNOUT_PIN(4); - #endif - #if NUM_RUNOUT_SENSORS >= 5 - INIT_RUNOUT_PIN(5); - #endif - #if NUM_RUNOUT_SENSORS >= 6 - INIT_RUNOUT_PIN(6); - #endif - #if NUM_RUNOUT_SENSORS >= 7 - INIT_RUNOUT_PIN(7); - #endif - #if NUM_RUNOUT_SENSORS >= 8 - INIT_RUNOUT_PIN(8); + #define _INIT_RUNOUT_PIN(P,S,U,D) do{ if (ENABLED(U)) SET_INPUT_PULLUP(P); else if (ENABLED(D)) SET_INPUT_PULLDOWN(P); else SET_INPUT(P); }while(0); + #define INIT_RUNOUT_PIN(N) _INIT_RUNOUT_PIN(FIL_RUNOUT##N##_PIN, FIL_RUNOUT##N##_STATE, FIL_RUNOUT##N##_PULLUP, FIL_RUNOUT##N##_PULLDOWN); + REPEAT_1(NUM_RUNOUT_SENSORS, INIT_RUNOUT_PIN) + #undef INIT_RUNOUT_PIN + + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + #define INIT_MOTION_PIN(N) _INIT_RUNOUT_PIN(FIL_MOTION##N##_PIN, FIL_MOTION##N##_STATE, FIL_MOTION##N##_PULLUP, FIL_MOTION##N##_PULLDOWN); + REPEAT_1(NUM_MOTION_SENSORS, INIT_MOTION_PIN) + #undef INIT_MOTION_PIN #endif #undef _INIT_RUNOUT_PIN - #undef INIT_RUNOUT_PIN } // Return a bitmask of runout pin states @@ -213,36 +223,29 @@ class FilamentSensorBase { // Return a bitmask of runout flag states (1 bits always indicates runout) static uint8_t poll_runout_states() { - return poll_runout_pins() ^ uint8_t(0 - #if NUM_RUNOUT_SENSORS >= 1 - | (FIL_RUNOUT1_STATE ? 0 : _BV(1 - 1)) - #endif - #if NUM_RUNOUT_SENSORS >= 2 - | (FIL_RUNOUT2_STATE ? 0 : _BV(2 - 1)) - #endif - #if NUM_RUNOUT_SENSORS >= 3 - | (FIL_RUNOUT3_STATE ? 0 : _BV(3 - 1)) - #endif - #if NUM_RUNOUT_SENSORS >= 4 - | (FIL_RUNOUT4_STATE ? 0 : _BV(4 - 1)) - #endif - #if NUM_RUNOUT_SENSORS >= 5 - | (FIL_RUNOUT5_STATE ? 0 : _BV(5 - 1)) - #endif - #if NUM_RUNOUT_SENSORS >= 6 - | (FIL_RUNOUT6_STATE ? 0 : _BV(6 - 1)) - #endif - #if NUM_RUNOUT_SENSORS >= 7 - | (FIL_RUNOUT7_STATE ? 0 : _BV(7 - 1)) - #endif - #if NUM_RUNOUT_SENSORS >= 8 - | (FIL_RUNOUT8_STATE ? 0 : _BV(8 - 1)) - #endif - ); + #define _INVERT_BIT(N) | (FIL_RUNOUT##N##_STATE ? 0 : _BV(N - 1)) + return poll_runout_pins() ^ uint8_t(0 REPEAT_1(NUM_RUNOUT_SENSORS, _INVERT_BIT)); + #undef _INVERT_BIT } + + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + // Return a bitmask of motion pin states + static uint8_t poll_motion_pins() { + #define _OR_MOTION(N) | (READ(FIL_MOTION##N##_PIN) ? _BV((N) - 1) : 0) + return (0 REPEAT_1(NUM_MOTION_SENSORS, _OR_MOTION)); + #undef _OR_MOTION + } + + // Return a bitmask of motion flag states (1 bits always indicates runout) + static uint8_t poll_motion_states() { + #define _OR_MOTION(N) | (FIL_MOTION##N##_STATE ? 0 : _BV(N - 1)) + return poll_motion_pins() ^ uint8_t(0 REPEAT_1(NUM_MOTION_SENSORS, _OR_MOTION)); + #undef _OR_MOTION + } + #endif }; -#if ENABLED(FILAMENT_MOTION_SENSOR) +#if HAS_FILAMENT_MOTION /** * This sensor uses a magnetic encoder disc and a Hall effect @@ -256,14 +259,14 @@ class FilamentSensorBase { static void poll_motion_sensor() { static uint8_t old_state; - const uint8_t new_state = poll_runout_pins(), + const uint8_t new_state = TERN(FILAMENT_SWITCH_AND_MOTION, poll_motion_pins, poll_runout_pins)(), change = old_state ^ new_state; old_state = new_state; #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) if (change) { SERIAL_ECHOPGM("Motion detected:"); - LOOP_L_N(e, NUM_RUNOUT_SENSORS) + for (uint8_t e = 0; e < TERN(FILAMENT_SWITCH_AND_MOTION, NUM_MOTION_SENSORS, NUM_RUNOUT_SENSORS); ++e) if (TEST(change, e)) SERIAL_CHAR(' ', '0' + e); SERIAL_EOL(); } @@ -273,11 +276,12 @@ class FilamentSensorBase { } public: + // Called from ISR context to indicate a block was completed static void block_completed(const block_t * const b) { // If the sensor wheel has moved since the last call to // this method reset the runout counter for the extruder. if (TEST(motion_detected, b->extruder)) - filament_present(b->extruder); + TERN(FILAMENT_SWITCH_AND_MOTION, filament_motion_present, filament_present)(b->extruder); // Clear motion triggers for next block motion_detected = 0; @@ -286,7 +290,9 @@ class FilamentSensorBase { static void run() { poll_motion_sensor(); } }; -#else +#endif // HAS_FILAMENT_MOTION + +#if HAS_FILAMENT_SWITCH /** * This is a simple endstop switch in the path of the filament. @@ -307,74 +313,195 @@ class FilamentSensorBase { } public: + // Called from ISR context to indicate a block was completed static void block_completed(const block_t * const) {} static void run() { - LOOP_L_N(s, NUM_RUNOUT_SENSORS) { + for (uint8_t s = 0; s < NUM_RUNOUT_SENSORS; ++s) { const bool out = poll_runout_state(s); if (!out) filament_present(s); #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) static uint8_t was_out; // = 0 if (out != TEST(was_out, s)) { TBI(was_out, s); - SERIAL_ECHOLNF(F("Filament Sensor "), AS_DIGIT(s), out ? F(" OUT") : F(" IN")); + SERIAL_ECHOLN(F("Filament Sensor "), AS_DIGIT(s), out ? F(" OUT") : F(" IN")); } #endif } } }; + #endif // HAS_FILAMENT_SWITCH -#endif // !FILAMENT_MOTION_SENSOR + /** + * This is a simple endstop switch in the path of the filament. + * It can detect filament runout, but not stripouts or jams. + */ + class FilamentSensor : public FilamentSensorBase { + private: + TERN_(HAS_FILAMENT_MOTION, static FilamentSensorEncoder encoder_sensor); + TERN_(HAS_FILAMENT_SWITCH, static FilamentSensorSwitch switch_sensor); + + public: + // Called from ISR context to indicate a block was completed + static void block_completed(const block_t * const b) { + TERN_(HAS_FILAMENT_MOTION, encoder_sensor.block_completed(b)); + TERN_(HAS_FILAMENT_SWITCH, switch_sensor.block_completed(b)); + } + + static void run() { + TERN_(HAS_FILAMENT_MOTION, encoder_sensor.run()); + TERN_(HAS_FILAMENT_SWITCH, switch_sensor.run()); + } + }; /********************************* RESPONSE TYPE *********************************/ #if HAS_FILAMENT_RUNOUT_DISTANCE + typedef struct { + float runout[NUM_RUNOUT_SENSORS]; + Flags runout_reset; // Reset runout later + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + float motion[NUM_MOTION_SENSORS]; + Flags motion_reset; // Reset motion later + #endif + } countdown_t; + // RunoutResponseDelayed triggers a runout event only if the length // of filament specified by FILAMENT_RUNOUT_DISTANCE_MM has been fed // during a runout condition. class RunoutResponseDelayed { private: - static volatile float runout_mm_countdown[NUM_RUNOUT_SENSORS]; + static countdown_t mm_countdown; + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + static bool ignore_motion; // Flag to ignore the encoder + #endif public: static float runout_distance_mm; + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + static float motion_distance_mm; + #endif + + static void set_ignore_motion(const bool ignore=true) { + UNUSED(ignore); + TERN_(FILAMENT_SWITCH_AND_MOTION, ignore_motion = ignore); + } + static void reset() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) filament_present(i); + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) filament_motion_present(i); + #endif + set_ignore_motion(false); } static void run() { #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) static millis_t t = 0; const millis_t ms = millis(); - if (ELAPSED(ms, t)) { - t = millis() + 1000UL; - LOOP_L_N(i, NUM_RUNOUT_SENSORS) - SERIAL_ECHOF(i ? F(", ") : F("Remaining mm: "), runout_mm_countdown[i]); - SERIAL_EOL(); - } + if (PENDING(ms, t)) return; + t = ms + 1000UL; + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) + SERIAL_ECHO(i ? F(", ") : F("Runout remaining mm: "), mm_countdown.runout[i]); + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) + SERIAL_ECHO(i ? F(", ") : F("Motion remaining mm: "), mm_countdown.motion[i]); + #endif + SERIAL_EOL(); #endif } - static uint8_t has_run_out() { - uint8_t runout_flags = 0; - LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_mm_countdown[i] < 0) SBI(runout_flags, i); + // Get runout status for all presence sensors and motion sensors + static runout_flags_t has_run_out() { + runout_flags_t runout_flags{0}; + + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + // Runout based on filament motion + if (!ignore_motion) { + for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) { + if (mm_countdown.motion[i] < 0) { + runout_flags.set(i); + mm_countdown.runout[i] = -1; // For a filament jam don't wait for runout_distance_mm! + } + } + } + #endif + + // Runout based on filament presence + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) + if (mm_countdown.runout[i] < 0) + runout_flags.set(i); + return runout_flags; } static void filament_present(const uint8_t extruder) { - runout_mm_countdown[extruder] = runout_distance_mm; + if (mm_countdown.runout[extruder] < runout_distance_mm || did_pause_print) { + // Reset runout only if it is smaller than runout_distance or printing is paused. + // On Bowden systems retract may be larger than runout_distance_mm, so if retract + // was added leave it in place, or the following unretract will cause runout event. + mm_countdown.runout[extruder] = runout_distance_mm; + mm_countdown.runout_reset.clear(extruder); + } + else { + // If runout is larger than runout distance, we cannot reset right now, as Bowden and retract + // distance larger than runout_distance_mm leads to negative runout right after unretract. + // But we cannot ignore filament_present event. After unretract, runout will become smaller + // than runout_distance_mm and should be reset after that. So activate delayed reset. + mm_countdown.runout_reset.set(extruder); + } } - static void block_completed(const block_t * const b) { - if (b->steps.x || b->steps.y || b->steps.z || did_pause_print) { // Allow pause purge move to re-trigger runout state - // Only trigger on extrusion with XYZ movement to allow filament change and retract/recover. - const uint8_t e = b->extruder; - const int32_t steps = b->steps.e; - runout_mm_countdown[e] -= (TEST(b->direction_bits, E_AXIS) ? -steps : steps) * planner.mm_per_step[E_AXIS_N(e)]; + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + static void filament_motion_present(const uint8_t extruder) { + // Same logic as filament_present + if (mm_countdown.motion[extruder] < motion_distance_mm || did_pause_print) { + mm_countdown.motion[extruder] = motion_distance_mm; + mm_countdown.motion_reset.clear(extruder); + } + else + mm_countdown.motion_reset.set(extruder); } + #endif + + // Called from ISR context to indicate a block was completed + static void block_completed(const block_t * const b) { + // No calculation unless paused or printing + if (!should_monitor_runout()) return; + + // Only extrusion moves are examined + const int32_t esteps = b->steps.e; + if (!esteps) return; + + // No need to ignore retract/unretract movement since they complement each other + const uint8_t e = b->extruder; + const float mm = (b->direction_bits.e ? esteps : -esteps) * planner.mm_per_step[E_AXIS_N(e)]; + + // Apply E distance to runout countdown, reset if flagged + if (e < NUM_RUNOUT_SENSORS) { + mm_countdown.runout[e] -= mm; + if (mm_countdown.runout_reset[e]) filament_present(e); // Reset pending. Try to reset. + } + + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + // Apply E distance to motion countdown, reset if flagged + if (!ignore_motion && e < NUM_MOTION_SENSORS) { + mm_countdown.motion[e] -= mm; + if (mm_countdown.motion_reset[e]) filament_motion_present(e); // Reset pending. Try to reset. + } + #endif + } + + // Reset after a filament runout or upon resuming a job + static void init_for_restart(const bool onoff=true) { + UNUSED(onoff); + #if ENABLED(FILAMENT_SWITCH_AND_MOTION) + reset(); // also calls set_ignore_motion(false) + set_ignore_motion(!onoff); + #endif } }; @@ -390,24 +517,28 @@ class FilamentSensorBase { public: static void reset() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) filament_present(i); } static void run() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] >= 0) runout_count[i]--; + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (runout_count[i] >= 0) runout_count[i]--; } - static uint8_t has_run_out() { - uint8_t runout_flags = 0; - LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] < 0) SBI(runout_flags, i); + static runout_flags_t has_run_out() { + runout_flags_t runout_flags{0}; + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (runout_count[i] < 0) runout_flags.set(i); return runout_flags; } + // Called from ISR context to indicate a block was completed static void block_completed(const block_t * const) { } static void filament_present(const uint8_t extruder) { runout_count[extruder] = runout_threshold; } + + // Reset after a filament runout or upon resuming a job + static void init_for_restart(const bool=true) { reset(); } }; #endif // !HAS_FILAMENT_RUNOUT_DISTANCE diff --git a/Marlin/src/feature/solenoid.cpp b/Marlin/src/feature/solenoid.cpp index 861e44ed05..cc4522e30a 100644 --- a/Marlin/src/feature/solenoid.cpp +++ b/Marlin/src/feature/solenoid.cpp @@ -22,12 +22,12 @@ #include "../inc/MarlinConfig.h" -#if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) +#if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) #include "solenoid.h" #include "../module/motion.h" // for active_extruder -#include "../module/tool_change.h" +#include "../module/tool_change.h" // for parking_extruder_set_parked // Used primarily with MANUAL_SOLENOID_CONTROL static void set_solenoid(const uint8_t num, const uint8_t state) { diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index e7898268e8..dd8d859bde 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -35,7 +35,7 @@ #endif #if ENABLED(I2C_AMMETER) - #include "../feature/ammeter.h" + #include "ammeter.h" #endif SpindleLaser cutter; @@ -43,6 +43,10 @@ bool SpindleLaser::enable_state; // Virtual 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 HAS_SPINDLE_ACCELERATION + uint32_t SpindleLaser::acceleration_spindle_deg_per_s2; // (°/s/s) Spindle acceleration. Initialized by settings.load +#endif + #if ENABLED(LASER_FEATURE) 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 @@ -100,7 +104,22 @@ void SpindleLaser::init() { #if ENABLED(HAL_CAN_SET_PWM_FREQ) && 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); + #if HAS_SPINDLE_ACCELERATION + const int16_t diff = ocr - last_power_applied; + const uint8_t abs_diff = ABS(diff); + uint8_t current_ocr = last_power_applied; + // Duration between ocr increments. SPEED_POWER_MAX is in RPM. + const millis_t duration = (float(SPEED_POWER_MAX) * (60000.f / 2550.f) / float(acceleration_spindle_deg_per_s2)) * abs_diff; + millis_t next_ocr_change = millis() + duration; + while (current_ocr != ocr) { + while (PENDING(millis(), next_ocr_change)) marlin.idle(); + current_ocr += diff > 0 ? 1 : -1; + hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), current_ocr ^ SPINDLE_LASER_PWM_OFF); + next_ocr_change += duration; + } + #else + hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); + #endif } void SpindleLaser::set_ocr(const uint8_t ocr) { @@ -111,10 +130,10 @@ void SpindleLaser::init() { } void SpindleLaser::ocr_off() { + _set_ocr(0); #if PIN_EXISTS(SPINDLE_LASER_ENA) WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Cutter OFF #endif - _set_ocr(0); } #endif // SPINDLE_LASER_USE_PWM @@ -127,9 +146,8 @@ void SpindleLaser::init() { */ void SpindleLaser::apply_power(const uint8_t opwr) { 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 + // Test 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) @@ -141,11 +159,12 @@ void SpindleLaser::apply_power(const uint8_t opwr) { else ocr_off(); #elif ENABLED(SPINDLE_SERVO) - MOVE_SERVO(SPINDLE_SERVO_NR, power); + servo[SPINDLE_SERVO_NR].move(opwr); #else WRITE(SPINDLE_LASER_ENA_PIN, enabled() ? SPINDLE_LASER_ACTIVE_STATE : !SPINDLE_LASER_ACTIVE_STATE); isReadyForUI = true; #endif + last_power_applied = opwr; } else { #if PIN_EXISTS(SPINDLE_LASER_ENA) diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index b667da25bb..8305c1fec4 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -30,16 +30,17 @@ #include "spindle_laser_types.h" -#if HAS_BEEPER - #include "../libs/buzzer.h" -#endif +#include "../libs/buzzer.h" // Inline laser power #include "../module/planner.h" +#define RPM_TO_PWM(X) ((X) * 255 / (SPEED_POWER_MAX)) +#define PWM_TO_RPM(X) ((X) * (SPEED_POWER_MAX) / 255) #define PCT_TO_PWM(X) ((X) * 255 / 100) +#define PWM_TO_PCT(X) ((X) * 100 / 255) #define PCT_TO_SERVO(X) ((X) * 180 / 100) - +#define CUTTER_PWM_TO_SPWR(X) (CUTTER_UNIT_IS(PERCENT) ? PWM_TO_PCT(X) : (CUTTER_UNIT_IS(RPM) ? PWM_TO_RPM(X) : X)) // Laser/Cutter operation mode enum CutterMode : int8_t { @@ -53,13 +54,13 @@ class SpindleLaser { public: static CutterMode cutter_mode; - static constexpr uint8_t pct_to_ocr(const_float_t pct) { return uint8_t(PCT_TO_PWM(pct)); } + static constexpr uint8_t pct_to_ocr(const float pct) { return uint8_t(PCT_TO_PWM(pct)); } // cpower = configured values (e.g., SPEED_POWER_MAX) // Convert configured power range to a percentage 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; + return cpwr ? LROUND(100.0f * (cpwr - power_floor) / (SPEED_POWER_MAX - power_floor)) : 0; } // Convert config defines from RPM to %, angle or PWM when in Spindle mode @@ -108,11 +109,14 @@ public: static uint8_t power, last_power_applied; // Basic power state tracking - static cutter_frequency_t frequency; // Set PWM frequency; range: 2K-50K + static cutter_frequency_t frequency; // (Hz) Laser/Spindle PWM frequency (2000..50000) - 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 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 + #if HAS_SPINDLE_ACCELERATION + static uint32_t acceleration_spindle_deg_per_s2; // (°/s/s) Spindle acceleration + #endif static void init(); #if ENABLED(HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY @@ -160,7 +164,7 @@ public: */ 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)), + min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, roundf(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; @@ -203,8 +207,6 @@ public: 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; @@ -212,7 +214,7 @@ public: enable = false; apply_power(0); } - #if SPINDLE_LASER_ENA_PIN + #if PIN_EXISTS(SPINDLE_LASER_ENA) WRITE(SPINDLE_LASER_ENA_PIN, enable ? SPINDLE_LASER_ACTIVE_STATE : !SPINDLE_LASER_ACTIVE_STATE); #endif enable_state = enable; @@ -283,9 +285,9 @@ public: set_enabled(state); if (state) { if (!menuPower) menuPower = cpwr_to_upwr(SPEED_POWER_STARTUP); - power = upower_to_ocr(menuPower); + power = TERN(SPINDLE_LASER_USE_PWM, upower_to_ocr(menuPower), 255); apply_power(power); - } else + } else apply_power(0); } diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h index 2f36a68a1a..4e5e4d06f6 100644 --- a/Marlin/src/feature/spindle_laser_types.h +++ b/Marlin/src/feature/spindle_laser_types.h @@ -57,7 +57,7 @@ #endif #endif -typedef IF<(SPEED_POWER_MAX > 255), uint16_t, uint8_t>::type cutter_cpower_t; +typedef uvalue_t(SPEED_POWER_MAX) cutter_cpower_t; #if CUTTER_UNIT_IS(RPM) && SPEED_POWER_MAX > 255 typedef uint16_t cutter_power_t; diff --git a/Marlin/src/feature/stepper_driver_safety.cpp b/Marlin/src/feature/stepper_driver_safety.cpp index b8762da9b0..acdd695909 100644 --- a/Marlin/src/feature/stepper_driver_safety.cpp +++ b/Marlin/src/feature/stepper_driver_safety.cpp @@ -30,8 +30,7 @@ static uint32_t axis_plug_backward = 0; void stepper_driver_backward_error(FSTR_P const fstr) { SERIAL_ERROR_START(); - SERIAL_ECHOF(fstr); - SERIAL_ECHOLNPGM(" driver is backward!"); + SERIAL_ECHOLN(fstr, F(" driver is backward!")); ui.status_printf(2, F(S_FMT S_FMT), FTOP(fstr), GET_TEXT(MSG_DRIVER_BACKWARD)); } @@ -43,7 +42,7 @@ void stepper_driver_backward_check() { SET_INPUT(AXIS##_ENABLE_PIN); \ OUT_WRITE(AXIS##_STEP_PIN, false); \ delay(20); \ - if (READ(AXIS##_ENABLE_PIN) == false) { \ + if (READ(AXIS##_ENABLE_PIN) == LOW) { \ SBI(axis_plug_backward, BIT); \ stepper_driver_backward_error(F(STRINGIFY(AXIS))); \ } \ diff --git a/Marlin/src/feature/stepper_driver_safety.h b/Marlin/src/feature/stepper_driver_safety.h index 46edf3390d..ac3d8b64f9 100644 --- a/Marlin/src/feature/stepper_driver_safety.h +++ b/Marlin/src/feature/stepper_driver_safety.h @@ -21,7 +21,6 @@ */ #pragma once - #include "../inc/MarlinConfigPre.h" void stepper_driver_backward_check(); diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 0867686363..a91d435355 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -24,14 +24,23 @@ #if HAS_TRINAMIC_CONFIG +/** + * feature/tmc_util.cpp - Functions for debugging Trinamic stepper drivers. + * The main entry point is `tmc_report_all` which is called by M122 to collect + * and report diagnostic information about each enabled TMC driver. + */ + #include "tmc_util.h" -#include "../MarlinCore.h" #include "../module/stepper/indirection.h" #include "../module/printcounter.h" #include "../libs/duration_t.h" #include "../gcode/gcode.h" +#if ENABLED(SOVOL_SV06_RTS) + #include "../lcd/sovol_rts/sovol_rts.h" +#endif + #if ENABLED(TMC_DEBUG) #include "../libs/hex_print.h" #if ENABLED(MONITOR_DRIVER_STATUS) @@ -39,6 +48,10 @@ #endif #endif +#if ENABLED(EDITABLE_HOMING_CURRENT) + homing_current_t homing_current_mA; +#endif + /** * Check for over temperature or short to ground error flags. * Report and log warning of overtemperature condition. @@ -64,7 +77,7 @@ #endif ; #if ENABLED(TMC_DEBUG) - #if HAS_TMCX1X0 || HAS_TMC220x + #if HAS_TMCX1X0_OR_2240 || HAS_TMC220x uint8_t cs_actual; #endif #if HAS_STALLGUARD @@ -134,6 +147,67 @@ #endif // HAS_TMCX1X0 + #if HAS_DRIVER(TMC2240) + + #if ENABLED(TMC_DEBUG) + static uint32_t get_pwm_scale(TMC2240Stepper &st) { return st.PWM_SCALE(); } + #endif + + static TMC_driver_data get_driver_data(TMC2240Stepper &st) { + constexpr uint8_t OT_bp = 25, OTPW_bp = 26; + constexpr uint32_t S2G_bm = 0x18000000; + #if ENABLED(TMC_DEBUG) + constexpr uint16_t SG_RESULT_bm = 0x3FF; // 0:9 + constexpr uint8_t STEALTH_bp = 14; + constexpr uint32_t CS_ACTUAL_bm = 0x1F0000; // 16:20 + constexpr uint8_t STALL_GUARD_bp = 24; + constexpr uint8_t STST_bp = 31; + #endif + TMC_driver_data data; + const auto ds = data.drv_status = st.DRV_STATUS(); + #ifdef __AVR__ + + // 8-bit optimization saves up to 70 bytes of PROGMEM per axis + uint8_t spart; + #if ENABLED(TMC_DEBUG) + data.sg_result = ds & SG_RESULT_bm; + spart = ds >> 8; + data.is_stealth = TEST(spart, STEALTH_bp - 8); + spart = ds >> 16; + data.cs_actual = spart & (CS_ACTUAL_bm >> 16); + #endif + spart = ds >> 24; + data.is_ot = TEST(spart, OT_bp - 24); + data.is_otpw = TEST(spart, OTPW_bp - 24); + data.is_s2g = !!(spart & (S2G_bm >> 24)); + #if ENABLED(TMC_DEBUG) + data.is_stall = TEST(spart, STALL_GUARD_bp - 24); + data.is_standstill = TEST(spart, STST_bp - 24); + data.sg_result_reasonable = !data.is_standstill; // sg_result has no reasonable meaning while standstill + #endif + + #else // !__AVR__ + + data.is_ot = TEST(ds, OT_bp); + data.is_otpw = TEST(ds, OTPW_bp); + data.is_s2g = !!(ds & S2G_bm); + #if ENABLED(TMC_DEBUG) + constexpr uint8_t CS_ACTUAL_sb = 16; + data.sg_result = ds & SG_RESULT_bm; + data.is_stealth = TEST(ds, STEALTH_bp); + data.cs_actual = (ds & CS_ACTUAL_bm) >> CS_ACTUAL_sb; + data.is_stall = TEST(ds, STALL_GUARD_bp); + data.is_standstill = TEST(ds, STST_bp); + data.sg_result_reasonable = !data.is_standstill; // sg_result has no reasonable meaning while standstill + #endif + + #endif // !__AVR__ + + return data; + } + + #endif // TMC2240 + #if HAS_TMC220x #if ENABLED(TMC_DEBUG) @@ -207,54 +281,54 @@ if (data.is_ot) SERIAL_ECHOLNPGM("overtemperature"); if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit"); TERN_(TMC_DEBUG, tmc_report_all()); - kill(F("Driver error")); + TERN_(SOVOL_SV06_RTS, rts.gotoPage(ID_DriverError_L, ID_DriverError_D)); + marlin.kill(F("Driver error")); } #endif template void report_driver_otpw(TMC &st) { - char timestamp[14]; + MString<13> timestamp; duration_t elapsed = print_job_timer.duration(); const bool has_days = (elapsed.value > 60*60*24L); - (void)elapsed.toDigital(timestamp, has_days); - SERIAL_EOL(); - SERIAL_ECHO(timestamp); - SERIAL_ECHOPGM(": "); + (void)elapsed.toDigital(×tamp, has_days); + TSS('\n', timestamp, F(": ")).echo(); st.printLabel(); - SERIAL_ECHOLNPGM(" driver overtemperature warning! (", st.getMilliamps(), "mA)"); + SString<50>(F(" driver overtemperature warning! ("), st.getMilliamps(), F("mA)")).echoln(); } - template - void report_polled_driver_data(TMC &st, const TMC_driver_data &data) { - const uint32_t pwm_scale = get_pwm_scale(st); - st.printLabel(); - SERIAL_CHAR(':'); SERIAL_ECHO(pwm_scale); - #if ENABLED(TMC_DEBUG) - #if HAS_TMCX1X0 || HAS_TMC220x - SERIAL_CHAR('/'); SERIAL_ECHO(data.cs_actual); + #if ENABLED(TMC_DEBUG) + + template + void report_polled_driver_data(TMC &st, const TMC_driver_data &data) { + const uint32_t pwm_scale = get_pwm_scale(st); + st.printLabel(); + SString<60> report(':', pwm_scale); + #if HAS_TMCX1X0_OR_2240 || HAS_TMC220x + report.append('/', data.cs_actual); #endif #if HAS_STALLGUARD - SERIAL_CHAR('/'); + report += '/'; if (data.sg_result_reasonable) - SERIAL_ECHO(data.sg_result); + report += data.sg_result; else - SERIAL_CHAR('-'); + report += '-'; #endif - #endif - SERIAL_CHAR('|'); - if (st.error_count) SERIAL_CHAR('E'); // Error - if (data.is_ot) SERIAL_CHAR('O'); // Over-temperature - if (data.is_otpw) SERIAL_CHAR('W'); // over-temperature pre-Warning - #if ENABLED(TMC_DEBUG) - if (data.is_stall) SERIAL_CHAR('G'); // stallGuard - if (data.is_stealth) SERIAL_CHAR('T'); // stealthChop - if (data.is_standstill) SERIAL_CHAR('I'); // standstIll - #endif - if (st.flag_otpw) SERIAL_CHAR('F'); // otpw Flag - SERIAL_CHAR('|'); - if (st.otpw_count > 0) SERIAL_ECHO(st.otpw_count); - SERIAL_CHAR('\t'); - } + report += '|'; + if (st.error_count) report += 'E'; // Error + if (data.is_ot) report += 'O'; // Over-temperature + if (data.is_otpw) report += 'W'; // over-temperature pre-Warning + if (data.is_stall) report += 'G'; // stallGuard + if (data.is_stealth) report += 'T'; // stealthChop + if (data.is_standstill) report += 'I'; // standstIll + if (st.flag_otpw) report += 'F'; // otpw Flag + report += '|'; + if (st.otpw_count > 0) report += st.otpw_count; + report += '\t'; + report.echo(); + } + + #endif // TMC_DEBUG #if CURRENT_STEP_DOWN > 0 @@ -314,9 +388,9 @@ else if (st.otpw_count > 0) st.otpw_count = 0; } - #if ENABLED(TMC_DEBUG) - if (need_debug_reporting) report_polled_driver_data(st, data); - #endif + if (need_debug_reporting) { + TERN_(TMC_DEBUG, report_polled_driver_data(st, data)); + } return should_step_down; } @@ -340,127 +414,70 @@ if (need_update_error_counters || need_debug_reporting) { - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) - { - bool result = false; - #if AXIS_IS_TMC(X) - if (monitor_tmc_driver(stepperX, need_update_error_counters, need_debug_reporting)) result = true; - #endif - #if AXIS_IS_TMC(X2) - if (monitor_tmc_driver(stepperX2, need_update_error_counters, need_debug_reporting)) result = true; - #endif - if (result) { - #if AXIS_IS_TMC(X) - step_current_down(stepperX); - #endif - #if AXIS_IS_TMC(X2) - step_current_down(stepperX2); - #endif + #if X_IS_TRINAMIC || X2_IS_TRINAMIC + if ( TERN0(X_IS_TRINAMIC, monitor_tmc_driver(stepperX, need_update_error_counters, need_debug_reporting)) + || TERN0(X2_IS_TRINAMIC, monitor_tmc_driver(stepperX2, need_update_error_counters, need_debug_reporting)) + ) { + TERN_(X_IS_TRINAMIC, step_current_down(stepperX)); + TERN_(X2_IS_TRINAMIC, step_current_down(stepperX2)); } - } #endif - #if AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) - { - bool result = false; - #if AXIS_IS_TMC(Y) - if (monitor_tmc_driver(stepperY, need_update_error_counters, need_debug_reporting)) result = true; - #endif - #if AXIS_IS_TMC(Y2) - if (monitor_tmc_driver(stepperY2, need_update_error_counters, need_debug_reporting)) result = true; - #endif - if (result) { - #if AXIS_IS_TMC(Y) - step_current_down(stepperY); - #endif - #if AXIS_IS_TMC(Y2) - step_current_down(stepperY2); - #endif + #if Y_IS_TRINAMIC || Y2_IS_TRINAMIC + if ( TERN0(Y_IS_TRINAMIC, monitor_tmc_driver(stepperY, need_update_error_counters, need_debug_reporting)) + || TERN0(Y2_IS_TRINAMIC, monitor_tmc_driver(stepperY2, need_update_error_counters, need_debug_reporting)) + ) { + TERN_(Y_IS_TRINAMIC, step_current_down(stepperY)); + TERN_(Y2_IS_TRINAMIC, step_current_down(stepperY2)); } - } #endif - #if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) - { - bool result = false; - #if AXIS_IS_TMC(Z) - if (monitor_tmc_driver(stepperZ, need_update_error_counters, need_debug_reporting)) result = true; - #endif - #if AXIS_IS_TMC(Z2) - if (monitor_tmc_driver(stepperZ2, need_update_error_counters, need_debug_reporting)) result = true; - #endif - #if AXIS_IS_TMC(Z3) - if (monitor_tmc_driver(stepperZ3, need_update_error_counters, need_debug_reporting)) result = true; - #endif - #if AXIS_IS_TMC(Z4) - if (monitor_tmc_driver(stepperZ4, need_update_error_counters, need_debug_reporting)) result = true; - #endif - if (result) { - #if AXIS_IS_TMC(Z) - step_current_down(stepperZ); - #endif - #if AXIS_IS_TMC(Z2) - step_current_down(stepperZ2); - #endif - #if AXIS_IS_TMC(Z3) - step_current_down(stepperZ3); - #endif - #if AXIS_IS_TMC(Z4) - step_current_down(stepperZ4); - #endif + #if ANY(Z_IS_TRINAMIC, Z2_IS_TRINAMIC, Z3_IS_TRINAMIC, Z4_IS_TRINAMIC) + if ( TERN0(Z_IS_TRINAMIC, monitor_tmc_driver(stepperZ, need_update_error_counters, need_debug_reporting)) + || TERN0(Z2_IS_TRINAMIC, monitor_tmc_driver(stepperZ2, need_update_error_counters, need_debug_reporting)) + || TERN0(Z3_IS_TRINAMIC, monitor_tmc_driver(stepperZ3, need_update_error_counters, need_debug_reporting)) + || TERN0(Z4_IS_TRINAMIC, monitor_tmc_driver(stepperZ4, need_update_error_counters, need_debug_reporting)) + ) { + TERN_(Z_IS_TRINAMIC, step_current_down(stepperZ)); + TERN_(Z2_IS_TRINAMIC, step_current_down(stepperZ2)); + TERN_(Z3_IS_TRINAMIC, step_current_down(stepperZ3)); + TERN_(Z4_IS_TRINAMIC, step_current_down(stepperZ4)); } - } #endif - #if AXIS_IS_TMC(I) + #if I_IS_TRINAMIC if (monitor_tmc_driver(stepperI, need_update_error_counters, need_debug_reporting)) step_current_down(stepperI); #endif - #if AXIS_IS_TMC(J) + #if J_IS_TRINAMIC if (monitor_tmc_driver(stepperJ, need_update_error_counters, need_debug_reporting)) step_current_down(stepperJ); #endif - #if AXIS_IS_TMC(K) + #if K_IS_TRINAMIC if (monitor_tmc_driver(stepperK, need_update_error_counters, need_debug_reporting)) step_current_down(stepperK); #endif - #if AXIS_IS_TMC(U) + #if U_IS_TRINAMIC if (monitor_tmc_driver(stepperU, need_update_error_counters, need_debug_reporting)) step_current_down(stepperU); #endif - #if AXIS_IS_TMC(V) + #if V_IS_TRINAMIC if (monitor_tmc_driver(stepperV, need_update_error_counters, need_debug_reporting)) step_current_down(stepperV); #endif - #if AXIS_IS_TMC(W) + #if W_IS_TRINAMIC if (monitor_tmc_driver(stepperW, need_update_error_counters, need_debug_reporting)) step_current_down(stepperW); #endif - #if AXIS_IS_TMC(E0) - (void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting); - #endif - #if AXIS_IS_TMC(E1) - (void)monitor_tmc_driver(stepperE1, need_update_error_counters, need_debug_reporting); - #endif - #if AXIS_IS_TMC(E2) - (void)monitor_tmc_driver(stepperE2, need_update_error_counters, need_debug_reporting); - #endif - #if AXIS_IS_TMC(E3) - (void)monitor_tmc_driver(stepperE3, need_update_error_counters, need_debug_reporting); - #endif - #if AXIS_IS_TMC(E4) - (void)monitor_tmc_driver(stepperE4, need_update_error_counters, need_debug_reporting); - #endif - #if AXIS_IS_TMC(E5) - (void)monitor_tmc_driver(stepperE5, need_update_error_counters, need_debug_reporting); - #endif - #if AXIS_IS_TMC(E6) - (void)monitor_tmc_driver(stepperE6, need_update_error_counters, need_debug_reporting); - #endif - #if AXIS_IS_TMC(E7) - (void)monitor_tmc_driver(stepperE7, need_update_error_counters, need_debug_reporting); - #endif + TERN_(E0_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting)); + TERN_(E1_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE1, need_update_error_counters, need_debug_reporting)); + TERN_(E2_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE2, need_update_error_counters, need_debug_reporting)); + TERN_(E3_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE3, need_update_error_counters, need_debug_reporting)); + TERN_(E4_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE4, need_update_error_counters, need_debug_reporting)); + TERN_(E5_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE5, need_update_error_counters, need_debug_reporting)); + TERN_(E6_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE6, need_update_error_counters, need_debug_reporting)); + TERN_(E7_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE7, need_update_error_counters, need_debug_reporting)); if (TERN0(TMC_DEBUG, need_debug_reporting)) SERIAL_EOL(); } @@ -506,7 +523,7 @@ TMC_TSTEP, TMC_TPWMTHRS, TMC_TPWMTHRS_MMS, - TMC_OTPW, + TMC_DEBUG_OTPW, TMC_OTPW_TRIGGERED, TMC_TOFF, TMC_TBL, @@ -514,7 +531,12 @@ TMC_HSTRT, TMC_SGT, TMC_MSCNT, - TMC_INTERPOLATE + TMC_INTERPOLATE, + TMC_VAIN, + TMC_VSUPPLY, + TMC_TEMP, + TMC_OVERTEMP, + TMC_OVERVOLT_THD }; enum TMC_drv_status_enum : char { TMC_DRV_CODES, @@ -558,24 +580,49 @@ TMC_GET_DRVCTRL, TMC_GET_DRVSTATUS, TMC_GET_SGCSCONF, - TMC_GET_SMARTEN + TMC_GET_SMARTEN, + TMC_GET_SG4_THRS, + TMC_GET_SG4_RESULT }; template - static void print_vsense(TMC &st) { SERIAL_ECHOF(st.vsense() ? F("1=.18") : F("0=.325")); } + static void print_vsense(TMC &st) { SERIAL_ECHO(st.vsense() ? F("1=.18") : F("0=.325")); } + #if HAS_DRIVER(TMC2160) + template + void print_vsense(TMCMarlin &) { } + #endif + #if HAS_DRIVER(TMC5160) + template + void print_vsense(TMCMarlin &) { } + #endif + #if HAS_DRIVER(TMC2240) + template + void print_vsense(TMCMarlin &) { } + #endif + + template + void print_cs_actual(TMC &st) { SERIAL_ECHO(st.cs_actual(), F("/31")); } + #if HAS_DRIVER(TMC2240) + template + void print_cs_actual(TMCMarlin &) { } + #endif + + static void print_true_or_false(const bool tf) { SERIAL_ECHO(TRUE_FALSE(tf)); } #if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130) + // Additional tmc_status fields for 2130/5130 and related drivers static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) { switch (i) { case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break; case TMC_SGT: SERIAL_ECHO(st.sgt()); break; - case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break; - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + case TMC_STEALTHCHOP: print_true_or_false(st.en_pwm_mode()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } #endif #if HAS_TMCX1X0 + // Additional tmc_parse_drv_status fields for 2130 and related drivers static void _tmc_parse_drv_status(TMC2130Stepper &st, const TMC_drv_status_enum i) { switch (i) { case TMC_STALLGUARD: if (st.stallguard()) SERIAL_CHAR('*'); break; @@ -588,57 +635,56 @@ #endif #if HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5160) - template - void print_vsense(TMCMarlin &) { } - - template - void print_vsense(TMCMarlin &) { } - + // Additional tmc_status fields for 2160/5160 and related drivers static void _tmc_status(TMC2160Stepper &st, const TMC_debug_enum i) { switch (i) { case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break; case TMC_SGT: SERIAL_ECHO(st.sgt()); break; - case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break; - case TMC_GLOBAL_SCALER: - { - uint16_t value = st.GLOBAL_SCALER(); - SERIAL_ECHO(value ? value : 256); - SERIAL_ECHOPGM("/256"); - } - break; - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + case TMC_STEALTHCHOP: print_true_or_false(st.en_pwm_mode()); break; + case TMC_GLOBAL_SCALER: { + const uint16_t value = st.GLOBAL_SCALER(); + SERIAL_ECHO(value ?: 256); + SERIAL_ECHOPGM("/256"); + } break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } - #endif + #endif // TMC2160 || TMC5160 #if HAS_TMC220x + + // Additional tmc_status fields for 2208/2224/2209 drivers static void _tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) { switch (i) { + // PWM_SCALE case TMC_PWM_SCALE_SUM: SERIAL_ECHO(st.pwm_scale_sum()); break; case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break; + // PWM_AUTO case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break; case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break; - case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break; - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + // CHOPCONF + case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } #if HAS_DRIVER(TMC2209) + // Additional tmc_status fields for 2209 drivers template static void _tmc_status(TMCMarlin &st, const TMC_debug_enum i) { switch (i) { case TMC_SGT: SERIAL_ECHO(st.SGTHRS()); break; case TMC_UART_ADDR: SERIAL_ECHO(st.get_address()); break; default: - TMC2208Stepper *parent = &st; - _tmc_status(*parent, i); + _tmc_status(static_cast(st), i); break; } } #endif + // Additional tmc_parse_drv_status fields for 2208/2224/2209 drivers static void _tmc_parse_drv_status(TMC2208Stepper &st, const TMC_drv_status_enum i) { switch (i) { case TMC_T157: if (st.t157()) SERIAL_CHAR('*'); break; @@ -653,52 +699,99 @@ } #if HAS_DRIVER(TMC2209) + // Additional tmc_parse_drv_status fields for 2209 drivers static void _tmc_parse_drv_status(TMC2209Stepper &st, const TMC_drv_status_enum i) { switch (i) { case TMC_SG_RESULT: SERIAL_ECHO(st.SG_RESULT()); break; - default: _tmc_parse_drv_status(static_cast(st), i); break; + default: + _tmc_parse_drv_status(static_cast(st), i); + break; } } #endif - #endif + + #endif // HAS_TMC220x + + #if HAS_DRIVER(TMC2240) + + // Additional tmc_parse_drv_status fields for 2240 drivers + static void _tmc_parse_drv_status(TMC2240Stepper &st, const TMC_drv_status_enum i) { + switch (i) { + case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('*'); break; + case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('*'); break; + case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break; + case TMC_FSACTIVE: if (st.fsactive()) SERIAL_CHAR('*'); break; + case TMC_DRV_CS_ACTUAL: if (st.CS_ACTUAL()) SERIAL_CHAR('*'); break; + case TMC_STALLGUARD: if (st.stallguard()) SERIAL_CHAR('*'); break; + case TMC_OT: if (st.ot()) SERIAL_CHAR('*'); break; + case TMC_SG_RESULT: SERIAL_ECHO(st.SG_RESULT()); break; + default: break; // other... + } + } + + // Additional tmc_status fields for 2240 drivers + static void _tmc_status(TMC2240Stepper &st, const TMC_debug_enum i) { + switch (i) { + // PWM_SCALE + case TMC_PWM_SCALE_SUM: SERIAL_ECHO(st.pwm_scale_sum()); break; + case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break; + // PWM_AUTO + case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break; + case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break; + // CHOPCONF + case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; + case TMC_VAIN: SERIAL_ECHO(st.get_ain_voltage()); break; + case TMC_VSUPPLY: SERIAL_ECHO(st.get_vsupply_voltage()); break; + case TMC_TEMP: SERIAL_ECHO(st.get_chip_temperature()); break; + case TMC_OVERTEMP: SERIAL_ECHO(st.get_overtemp_prewarn_celsius()); break; + case TMC_OVERVOLT_THD: SERIAL_ECHO(st.get_overvoltage_threshold_voltage()); break; + default: break; + } + } + + #endif // TMC2240 #if HAS_DRIVER(TMC2660) static void _tmc_parse_drv_status(TMC2660Stepper, const TMC_drv_status_enum) { } static void _tmc_status(TMC2660Stepper &st, const TMC_debug_enum i) { switch (i) { - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } #endif + template + void print_tstep(TMC &st) { + const uint32_t tstep_value = st.TSTEP(); + if (tstep_value != 0xFFFFF) + SERIAL_ECHO(tstep_value); + else + SERIAL_ECHOPGM("max"); + } + void print_tstep(TMC2660Stepper &st) { } + + template + void print_blank_time(TMC &st) { SERIAL_ECHO(st.blank_time()); } + template + void print_blank_time(TMCMarlin &) { } + template static void tmc_status(TMC &st, const TMC_debug_enum i) { SERIAL_CHAR('\t'); switch (i) { case TMC_CODES: st.printLabel(); break; - case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break; + case TMC_ENABLED: print_true_or_false(st.isEnabled()); break; case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break; case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break; - case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break; - case TMC_IRUN: - SERIAL_ECHO(st.irun()); - SERIAL_ECHOPGM("/31"); - break; - case TMC_IHOLD: - SERIAL_ECHO(st.ihold()); - SERIAL_ECHOPGM("/31"); - break; - case TMC_CS_ACTUAL: - SERIAL_ECHO(st.cs_actual()); - SERIAL_ECHOPGM("/31"); - break; + case TMC_MAX_CURRENT: SERIAL_ECHO(p_float_t(st.rms_current() * 1.41, 0)); break; + case TMC_IRUN: SERIAL_ECHO(st.irun()); SERIAL_ECHOPGM("/31"); break; + case TMC_IHOLD: SERIAL_ECHO(st.ihold()); SERIAL_ECHOPGM("/31"); break; + case TMC_CS_ACTUAL: print_cs_actual(st); break; case TMC_VSENSE: print_vsense(st); break; case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break; - case TMC_TSTEP: { - const uint32_t tstep_value = st.TSTEP(); - if (tstep_value != 0xFFFFF) SERIAL_ECHO(tstep_value); else SERIAL_ECHOPGM("max"); - } break; + case TMC_TSTEP: print_tstep(st); break; #if ENABLED(HYBRID_THRESHOLD) case TMC_TPWMTHRS: SERIAL_ECHO(uint32_t(st.TPWMTHRS())); break; case TMC_TPWMTHRS_MMS: { @@ -706,12 +799,12 @@ if (tpwmthrs_val) SERIAL_ECHO(tpwmthrs_val); else SERIAL_CHAR('-'); } break; #endif - case TMC_OTPW: serialprint_truefalse(st.otpw()); break; + case TMC_DEBUG_OTPW: print_true_or_false(st.otpw()); break; #if ENABLED(MONITOR_DRIVER_STATUS) - case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; + case TMC_OTPW_TRIGGERED: print_true_or_false(st.getOTPW()); break; #endif case TMC_TOFF: SERIAL_ECHO(st.toff()); break; - case TMC_TBL: SERIAL_ECHO(st.blank_time()); break; + case TMC_TBL: print_blank_time(st); break; case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break; case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break; case TMC_MSCNT: SERIAL_ECHO(st.get_microstep_counter()); break; @@ -725,215 +818,121 @@ SERIAL_CHAR('\t'); switch (i) { case TMC_CODES: st.printLabel(); break; - case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break; + case TMC_ENABLED: print_true_or_false(st.isEnabled()); break; case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break; case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break; - case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break; - case TMC_IRUN: - SERIAL_ECHO(st.cs()); - SERIAL_ECHOPGM("/31"); - break; - case TMC_VSENSE: SERIAL_ECHOF(st.vsense() ? F("1=.165") : F("0=.310")); break; + case TMC_MAX_CURRENT: SERIAL_ECHO(p_float_t(st.rms_current() * 1.41, 0)); break; + case TMC_IRUN: SERIAL_ECHO(st.cs()); SERIAL_ECHOPGM("/31"); break; + case TMC_VSENSE: SERIAL_ECHO(st.vsense() ? F("1=.165") : F("0=.310")); break; case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break; - //case TMC_OTPW: serialprint_truefalse(st.otpw()); break; - //case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; + //case TMC_DEBUG_OTPW: print_true_or_false(st.otpw()); break; + //case TMC_OTPW_TRIGGERED: print_true_or_false(st.getOTPW()); break; case TMC_SGT: SERIAL_ECHO(st.sgt()); break; case TMC_TOFF: SERIAL_ECHO(st.toff()); break; - case TMC_TBL: SERIAL_ECHO(st.blank_time()); break; + case TMC_TBL: print_blank_time(st); break; case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break; case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break; - default: break; + default: _tmc_status(st, i); break; } } - #endif + #endif // TMC2660 template static void tmc_parse_drv_status(TMC &st, const TMC_drv_status_enum i) { SERIAL_CHAR('\t'); switch (i) { - case TMC_DRV_CODES: st.printLabel(); break; - case TMC_STST: if (!st.stst()) SERIAL_CHAR('*'); break; - case TMC_OLB: if (st.olb()) SERIAL_CHAR('*'); break; - case TMC_OLA: if (st.ola()) SERIAL_CHAR('*'); break; - case TMC_S2GB: if (st.s2gb()) SERIAL_CHAR('*'); break; - case TMC_S2GA: if (st.s2ga()) SERIAL_CHAR('*'); break; - case TMC_DRV_OTPW: if (st.otpw()) SERIAL_CHAR('*'); break; - case TMC_OT: if (st.ot()) SERIAL_CHAR('*'); break; + case TMC_DRV_CODES: st.printLabel(); break; + case TMC_STST: if (!st.stst()) SERIAL_CHAR('*'); break; + case TMC_OLB: if (st.olb()) SERIAL_CHAR('*'); break; + case TMC_OLA: if (st.ola()) SERIAL_CHAR('*'); break; + case TMC_S2GB: if (st.s2gb()) SERIAL_CHAR('*'); break; + case TMC_S2GA: if (st.s2ga()) SERIAL_CHAR('*'); break; + case TMC_DRV_OTPW: if (st.otpw()) SERIAL_CHAR('*'); break; + case TMC_OT: if (st.ot()) SERIAL_CHAR('*'); break; case TMC_DRV_STATUS_HEX: { const uint32_t drv_status = st.DRV_STATUS(); - SERIAL_CHAR('\t'); - st.printLabel(); - SERIAL_CHAR('\t'); - print_hex_long(drv_status, ':'); + SERIAL_CHAR('\t'); st.printLabel(); + SERIAL_CHAR('\t'); print_hex_long(drv_status, ':', true); if (drv_status == 0xFFFFFFFF || drv_status == 0) SERIAL_ECHOPGM("\t Bad response!"); SERIAL_EOL(); - break; - } + } break; default: _tmc_parse_drv_status(st, i); break; } } - static void tmc_debug_loop(const TMC_debug_enum n, LOGICAL_AXIS_ARGS(const bool)) { - if (x) { - #if AXIS_IS_TMC(X) - tmc_status(stepperX, n); - #endif - #if AXIS_IS_TMC(X2) - tmc_status(stepperX2, n); - #endif + static void tmc_debug_loop(const TMC_debug_enum n OPTARGS_LOGICAL(const bool)) { + if (TERN0(HAS_X_AXIS, x)) { + TERN_(X_IS_TRINAMIC, tmc_status(stepperX, n)); + TERN_(X2_IS_TRINAMIC, tmc_status(stepperX2, n)); } if (TERN0(HAS_Y_AXIS, y)) { - #if AXIS_IS_TMC(Y) - tmc_status(stepperY, n); - #endif - #if AXIS_IS_TMC(Y2) - tmc_status(stepperY2, n); - #endif + TERN_(Y_IS_TRINAMIC, tmc_status(stepperY, n)); + TERN_(Y2_IS_TRINAMIC, tmc_status(stepperY2, n)); } if (TERN0(HAS_Z_AXIS, z)) { - #if AXIS_IS_TMC(Z) - tmc_status(stepperZ, n); - #endif - #if AXIS_IS_TMC(Z2) - tmc_status(stepperZ2, n); - #endif - #if AXIS_IS_TMC(Z3) - tmc_status(stepperZ3, n); - #endif - #if AXIS_IS_TMC(Z4) - tmc_status(stepperZ4, n); - #endif + TERN_(Z_IS_TRINAMIC, tmc_status(stepperZ, n)); + TERN_(Z2_IS_TRINAMIC, tmc_status(stepperZ2, n)); + TERN_(Z3_IS_TRINAMIC, tmc_status(stepperZ3, n)); + TERN_(Z4_IS_TRINAMIC, tmc_status(stepperZ4, n)); } - #if AXIS_IS_TMC(I) - if (i) tmc_status(stepperI, n); - #endif - #if AXIS_IS_TMC(J) - if (j) tmc_status(stepperJ, n); - #endif - #if AXIS_IS_TMC(K) - if (k) tmc_status(stepperK, n); - #endif - #if AXIS_IS_TMC(U) - if (u) tmc_status(stepperU, n); - #endif - #if AXIS_IS_TMC(V) - if (v) tmc_status(stepperV, n); - #endif - #if AXIS_IS_TMC(W) - if (w) tmc_status(stepperW, n); - #endif + TERN_(I_IS_TRINAMIC, if (i) tmc_status(stepperI, n)); + TERN_(J_IS_TRINAMIC, if (j) tmc_status(stepperJ, n)); + TERN_(K_IS_TRINAMIC, if (k) tmc_status(stepperK, n)); + TERN_(U_IS_TRINAMIC, if (u) tmc_status(stepperU, n)); + TERN_(V_IS_TRINAMIC, if (v) tmc_status(stepperV, n)); + TERN_(W_IS_TRINAMIC, if (w) tmc_status(stepperW, n)); if (TERN0(HAS_EXTRUDERS, e)) { - #if AXIS_IS_TMC(E0) - tmc_status(stepperE0, n); - #endif - #if AXIS_IS_TMC(E1) - tmc_status(stepperE1, n); - #endif - #if AXIS_IS_TMC(E2) - tmc_status(stepperE2, n); - #endif - #if AXIS_IS_TMC(E3) - tmc_status(stepperE3, n); - #endif - #if AXIS_IS_TMC(E4) - tmc_status(stepperE4, n); - #endif - #if AXIS_IS_TMC(E5) - tmc_status(stepperE5, n); - #endif - #if AXIS_IS_TMC(E6) - tmc_status(stepperE6, n); - #endif - #if AXIS_IS_TMC(E7) - tmc_status(stepperE7, n); - #endif + TERN_(E0_IS_TRINAMIC, tmc_status(stepperE0, n)); + TERN_(E1_IS_TRINAMIC, tmc_status(stepperE1, n)); + TERN_(E2_IS_TRINAMIC, tmc_status(stepperE2, n)); + TERN_(E3_IS_TRINAMIC, tmc_status(stepperE3, n)); + TERN_(E4_IS_TRINAMIC, tmc_status(stepperE4, n)); + TERN_(E5_IS_TRINAMIC, tmc_status(stepperE5, n)); + TERN_(E6_IS_TRINAMIC, tmc_status(stepperE6, n)); + TERN_(E7_IS_TRINAMIC, tmc_status(stepperE7, n)); } SERIAL_EOL(); } - static void drv_status_loop(const TMC_drv_status_enum n, LOGICAL_AXIS_ARGS(const bool)) { - if (x) { - #if AXIS_IS_TMC(X) - tmc_parse_drv_status(stepperX, n); - #endif - #if AXIS_IS_TMC(X2) - tmc_parse_drv_status(stepperX2, n); - #endif + static void drv_status_loop(const TMC_drv_status_enum n OPTARGS_LOGICAL(const bool)) { + if (TERN0(HAS_X_AXIS, x)) { + TERN_(X_IS_TRINAMIC, tmc_parse_drv_status(stepperX, n)); + TERN_(X2_IS_TRINAMIC, tmc_parse_drv_status(stepperX2, n)); } if (TERN0(HAS_Y_AXIS, y)) { - #if AXIS_IS_TMC(Y) - tmc_parse_drv_status(stepperY, n); - #endif - #if AXIS_IS_TMC(Y2) - tmc_parse_drv_status(stepperY2, n); - #endif + TERN_(Y_IS_TRINAMIC, tmc_parse_drv_status(stepperY, n)); + TERN_(Y2_IS_TRINAMIC, tmc_parse_drv_status(stepperY2, n)); } if (TERN0(HAS_Z_AXIS, z)) { - #if AXIS_IS_TMC(Z) - tmc_parse_drv_status(stepperZ, n); - #endif - #if AXIS_IS_TMC(Z2) - tmc_parse_drv_status(stepperZ2, n); - #endif - #if AXIS_IS_TMC(Z3) - tmc_parse_drv_status(stepperZ3, n); - #endif - #if AXIS_IS_TMC(Z4) - tmc_parse_drv_status(stepperZ4, n); - #endif + TERN_(Z_IS_TRINAMIC, tmc_parse_drv_status(stepperZ, n)); + TERN_(Z2_IS_TRINAMIC, tmc_parse_drv_status(stepperZ2, n)); + TERN_(Z3_IS_TRINAMIC, tmc_parse_drv_status(stepperZ3, n)); + TERN_(Z4_IS_TRINAMIC, tmc_parse_drv_status(stepperZ4, n)); } - #if AXIS_IS_TMC(I) - if (i) tmc_parse_drv_status(stepperI, n); - #endif - #if AXIS_IS_TMC(J) - if (j) tmc_parse_drv_status(stepperJ, n); - #endif - #if AXIS_IS_TMC(K) - if (k) tmc_parse_drv_status(stepperK, n); - #endif - #if AXIS_IS_TMC(U) - if (u) tmc_parse_drv_status(stepperU, n); - #endif - #if AXIS_IS_TMC(V) - if (v) tmc_parse_drv_status(stepperV, n); - #endif - #if AXIS_IS_TMC(W) - if (w) tmc_parse_drv_status(stepperW, n); - #endif + TERN_(I_IS_TRINAMIC, if (i) tmc_parse_drv_status(stepperI, n)); + TERN_(J_IS_TRINAMIC, if (j) tmc_parse_drv_status(stepperJ, n)); + TERN_(K_IS_TRINAMIC, if (k) tmc_parse_drv_status(stepperK, n)); + TERN_(U_IS_TRINAMIC, if (u) tmc_parse_drv_status(stepperU, n)); + TERN_(V_IS_TRINAMIC, if (v) tmc_parse_drv_status(stepperV, n)); + TERN_(W_IS_TRINAMIC, if (w) tmc_parse_drv_status(stepperW, n)); if (TERN0(HAS_EXTRUDERS, e)) { - #if AXIS_IS_TMC(E0) - tmc_parse_drv_status(stepperE0, n); - #endif - #if AXIS_IS_TMC(E1) - tmc_parse_drv_status(stepperE1, n); - #endif - #if AXIS_IS_TMC(E2) - tmc_parse_drv_status(stepperE2, n); - #endif - #if AXIS_IS_TMC(E3) - tmc_parse_drv_status(stepperE3, n); - #endif - #if AXIS_IS_TMC(E4) - tmc_parse_drv_status(stepperE4, n); - #endif - #if AXIS_IS_TMC(E5) - tmc_parse_drv_status(stepperE5, n); - #endif - #if AXIS_IS_TMC(E6) - tmc_parse_drv_status(stepperE6, n); - #endif - #if AXIS_IS_TMC(E7) - tmc_parse_drv_status(stepperE7, n); - #endif + TERN_(E0_IS_TRINAMIC, tmc_parse_drv_status(stepperE0, n)); + TERN_(E1_IS_TRINAMIC, tmc_parse_drv_status(stepperE1, n)); + TERN_(E2_IS_TRINAMIC, tmc_parse_drv_status(stepperE2, n)); + TERN_(E3_IS_TRINAMIC, tmc_parse_drv_status(stepperE3, n)); + TERN_(E4_IS_TRINAMIC, tmc_parse_drv_status(stepperE4, n)); + TERN_(E5_IS_TRINAMIC, tmc_parse_drv_status(stepperE5, n)); + TERN_(E6_IS_TRINAMIC, tmc_parse_drv_status(stepperE6, n)); + TERN_(E7_IS_TRINAMIC, tmc_parse_drv_status(stepperE7, n)); } SERIAL_EOL(); @@ -943,9 +942,9 @@ * M122 report functions */ - void tmc_report_all(LOGICAL_AXIS_ARGS(const bool)) { - #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0) - #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0) + void tmc_report_all(LOGICAL_AXIS_ARGS_LC(const bool)) { + #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM OPTARGS_LOGICAL()); }while(0) + #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM OPTARGS_LOGICAL()); }while(0) TMC_REPORT("\t", TMC_CODES); #if HAS_DRIVER(TMC2209) @@ -971,16 +970,16 @@ TMC_REPORT("tstep\t", TMC_TSTEP); TMC_REPORT("PWM thresh.", TMC_TPWMTHRS); TMC_REPORT("[mm/s]\t", TMC_TPWMTHRS_MMS); - TMC_REPORT("OT prewarn", TMC_OTPW); + TMC_REPORT("OT prewarn", TMC_DEBUG_OTPW); #if ENABLED(MONITOR_DRIVER_STATUS) - TMC_REPORT("triggered\n OTP\t", TMC_OTPW_TRIGGERED); + TMC_REPORT("OTPW trig.\t", TMC_OTPW_TRIGGERED); #endif #if HAS_TMC220x - TMC_REPORT("pwm scale sum", TMC_PWM_SCALE_SUM); - TMC_REPORT("pwm scale auto", TMC_PWM_SCALE_AUTO); - TMC_REPORT("pwm offset auto", TMC_PWM_OFS_AUTO); - TMC_REPORT("pwm grad auto", TMC_PWM_GRAD_AUTO); + TMC_REPORT("pwm scale sum", TMC_PWM_SCALE_SUM); + TMC_REPORT("pwm scale auto", TMC_PWM_SCALE_AUTO); + TMC_REPORT("pwm offset auto", TMC_PWM_OFS_AUTO); + TMC_REPORT("pwm grad auto", TMC_PWM_GRAD_AUTO); #endif TMC_REPORT("off time", TMC_TOFF); @@ -989,11 +988,12 @@ TMC_REPORT(" -start\t", TMC_HSTRT); TMC_REPORT("Stallguard thrs", TMC_SGT); TMC_REPORT("uStep count", TMC_MSCNT); + DRV_REPORT("DRVSTATUS", TMC_DRV_CODES); - #if HAS_TMCX1X0 || HAS_TMC220x + #if HAS_TMCX1X0_OR_2240 || HAS_TMC220x DRV_REPORT("sg_result", TMC_SG_RESULT); #endif - #if HAS_TMCX1X0 + #if HAS_TMCX1X0_OR_2240 DRV_REPORT("stallguard", TMC_STALLGUARD); DRV_REPORT("fsactive", TMC_FSACTIVE); #endif @@ -1009,30 +1009,40 @@ DRV_REPORT("150C\t", TMC_T150); DRV_REPORT("143C\t", TMC_T143); DRV_REPORT("120C\t", TMC_T120); + #endif + #if HAS_TMC220x || HAS_DRIVER(TMC2240) DRV_REPORT("s2vsa\t", TMC_S2VSA); DRV_REPORT("s2vsb\t", TMC_S2VSB); #endif - DRV_REPORT("Driver registers:\n",TMC_DRV_STATUS_HEX); + DRV_REPORT("Driver registers:\n", TMC_DRV_STATUS_HEX); + #if HAS_DRIVER(TMC2240) + TMC_REPORT("Analog in (v)", TMC_VAIN); + TMC_REPORT("Supply (v)", TMC_VSUPPLY); + TMC_REPORT("Temp (°C)", TMC_TEMP); + TMC_REPORT("OT pre warn (°C)", TMC_OVERTEMP); + TMC_REPORT("OV threshold (v)", TMC_OVERVOLT_THD); + #endif SERIAL_EOL(); } #define PRINT_TMC_REGISTER(REG_CASE) case TMC_GET_##REG_CASE: print_hex_long(st.REG_CASE(), ':'); break - #if HAS_TMCX1X0 - static void tmc_get_ic_registers(TMC2130Stepper &st, const TMC_get_registers_enum i) { - switch (i) { - PRINT_TMC_REGISTER(TCOOLTHRS); - PRINT_TMC_REGISTER(THIGH); - PRINT_TMC_REGISTER(COOLCONF); - default: SERIAL_CHAR('\t'); break; - } - } - #endif - #if HAS_TMC220x - static void tmc_get_ic_registers(TMC2208Stepper, const TMC_get_registers_enum) { SERIAL_CHAR('\t'); } - #endif - #if HAS_TRINAMIC_CONFIG + + template + static void tmc_get_ic_registers(TMC &, const TMC_get_registers_enum) { SERIAL_CHAR('\t'); } + + #if HAS_TMCX1X0 + static void tmc_get_ic_registers(TMC2130Stepper &st, const TMC_get_registers_enum i) { + switch (i) { + PRINT_TMC_REGISTER(TCOOLTHRS); + PRINT_TMC_REGISTER(THIGH); + PRINT_TMC_REGISTER(COOLCONF); + default: SERIAL_CHAR('\t'); break; + } + } + #endif + template static void tmc_get_registers(TMC &st, const TMC_get_registers_enum i) { switch (i) { @@ -1052,7 +1062,9 @@ } SERIAL_CHAR('\t'); } - #endif + + #endif // HAS_TRINAMIC_CONFIG + #if HAS_DRIVER(TMC2660) template static void tmc_get_registers(TMCMarlin &st, const TMC_get_registers_enum i) { @@ -1070,91 +1082,47 @@ } #endif - static void tmc_get_registers(TMC_get_registers_enum n, LOGICAL_AXIS_ARGS(const bool)) { - if (x) { - #if AXIS_IS_TMC(X) - tmc_get_registers(stepperX, n); - #endif - #if AXIS_IS_TMC(X2) - tmc_get_registers(stepperX2, n); - #endif + static void tmc_get_registers(TMC_get_registers_enum n OPTARGS_LOGICAL(const bool)) { + if (TERN0(HAS_X_AXIS, x)) { + TERN_(X_IS_TRINAMIC, tmc_get_registers(stepperX, n)); + TERN_(X2_IS_TRINAMIC, tmc_get_registers(stepperX2, n)); } if (TERN0(HAS_Y_AXIS, y)) { - #if AXIS_IS_TMC(Y) - tmc_get_registers(stepperY, n); - #endif - #if AXIS_IS_TMC(Y2) - tmc_get_registers(stepperY2, n); - #endif + TERN_(Y_IS_TRINAMIC, tmc_get_registers(stepperY, n)); + TERN_(Y2_IS_TRINAMIC, tmc_get_registers(stepperY2, n)); } if (TERN0(HAS_Z_AXIS, z)) { - #if AXIS_IS_TMC(Z) - tmc_get_registers(stepperZ, n); - #endif - #if AXIS_IS_TMC(Z2) - tmc_get_registers(stepperZ2, n); - #endif - #if AXIS_IS_TMC(Z3) - tmc_get_registers(stepperZ3, n); - #endif - #if AXIS_IS_TMC(Z4) - tmc_get_registers(stepperZ4, n); - #endif + TERN_(Z_IS_TRINAMIC, tmc_get_registers(stepperZ, n)); + TERN_(Z2_IS_TRINAMIC, tmc_get_registers(stepperZ2, n)); + TERN_(Z3_IS_TRINAMIC, tmc_get_registers(stepperZ3, n)); + TERN_(Z4_IS_TRINAMIC, tmc_get_registers(stepperZ4, n)); } - #if AXIS_IS_TMC(I) - if (i) tmc_get_registers(stepperI, n); - #endif - #if AXIS_IS_TMC(J) - if (j) tmc_get_registers(stepperJ, n); - #endif - #if AXIS_IS_TMC(K) - if (k) tmc_get_registers(stepperK, n); - #endif - #if AXIS_IS_TMC(U) - if (u) tmc_get_registers(stepperU, n); - #endif - #if AXIS_IS_TMC(V) - if (v) tmc_get_registers(stepperV, n); - #endif - #if AXIS_IS_TMC(W) - if (w) tmc_get_registers(stepperW, n); - #endif + TERN_(I_IS_TRINAMIC, if (i) tmc_get_registers(stepperI, n)); + TERN_(J_IS_TRINAMIC, if (j) tmc_get_registers(stepperJ, n)); + TERN_(K_IS_TRINAMIC, if (k) tmc_get_registers(stepperK, n)); + TERN_(U_IS_TRINAMIC, if (u) tmc_get_registers(stepperU, n)); + TERN_(V_IS_TRINAMIC, if (v) tmc_get_registers(stepperV, n)); + TERN_(W_IS_TRINAMIC, if (w) tmc_get_registers(stepperW, n)); if (TERN0(HAS_EXTRUDERS, e)) { - #if AXIS_IS_TMC(E0) - tmc_get_registers(stepperE0, n); - #endif - #if AXIS_IS_TMC(E1) - tmc_get_registers(stepperE1, n); - #endif - #if AXIS_IS_TMC(E2) - tmc_get_registers(stepperE2, n); - #endif - #if AXIS_IS_TMC(E3) - tmc_get_registers(stepperE3, n); - #endif - #if AXIS_IS_TMC(E4) - tmc_get_registers(stepperE4, n); - #endif - #if AXIS_IS_TMC(E5) - tmc_get_registers(stepperE5, n); - #endif - #if AXIS_IS_TMC(E6) - tmc_get_registers(stepperE6, n); - #endif - #if AXIS_IS_TMC(E7) - tmc_get_registers(stepperE7, n); - #endif + TERN_(E0_IS_TRINAMIC, tmc_get_registers(stepperE0, n)); + TERN_(E1_IS_TRINAMIC, tmc_get_registers(stepperE1, n)); + TERN_(E2_IS_TRINAMIC, tmc_get_registers(stepperE2, n)); + TERN_(E3_IS_TRINAMIC, tmc_get_registers(stepperE3, n)); + TERN_(E4_IS_TRINAMIC, tmc_get_registers(stepperE4, n)); + TERN_(E5_IS_TRINAMIC, tmc_get_registers(stepperE5, n)); + TERN_(E6_IS_TRINAMIC, tmc_get_registers(stepperE6, n)); + TERN_(E7_IS_TRINAMIC, tmc_get_registers(stepperE7, n)); } SERIAL_EOL(); } - void tmc_get_registers(LOGICAL_AXIS_ARGS(bool)) { - #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_ARGS()); }while(0) + void tmc_get_registers(LOGICAL_AXIS_ARGS_LC(bool)) { + #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM OPTARGS_LOGICAL()); }while(0) #define TMC_GET_REG(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME) _TMC_GET_REG("\t", TMC_AXIS_CODES); TMC_GET_REG(GCONF, "\t\t"); @@ -1204,11 +1172,29 @@ st.TCOOLTHRS(0); } + bool tmc_enable_stallguard(TMC2240Stepper &st) { + const bool stealthchop_was_enabled = st.en_pwm_mode(); + + // TODO: Use StallGuard4 when stealthChop is enabled + // and leave stealthChop state unchanged. + + st.TCOOLTHRS(0xFFFFF); + st.en_pwm_mode(false); + st.diag0_stall(true); + + return stealthchop_was_enabled; + } + void tmc_disable_stallguard(TMC2240Stepper &st, const bool restore_stealth) { + st.TCOOLTHRS(0); + st.en_pwm_mode(restore_stealth); + st.diag0_stall(false); + } + bool tmc_enable_stallguard(TMC2660Stepper) { // TODO return false; } - void tmc_disable_stallguard(TMC2660Stepper, const bool) {}; + void tmc_disable_stallguard(TMC2660Stepper, const bool) { } #endif // USE_SENSORLESS @@ -1228,166 +1214,50 @@ static bool test_connection(TMC &st) { case 1: stat = F("HIGH"); break; case 2: stat = F("LOW"); break; } - SERIAL_ECHOLNF(stat); + SERIAL_ECHOLN(stat); return test_result; } -void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) { +void test_tmc_connection(LOGICAL_AXIS_ARGS_LC(const bool)) { uint8_t axis_connection = 0; - if (x) { - #if AXIS_IS_TMC(X) - axis_connection += test_connection(stepperX); - #endif - #if AXIS_IS_TMC(X2) - axis_connection += test_connection(stepperX2); - #endif + if (TERN0(HAS_X_AXIS, x)) { + TERN_(X_IS_TRINAMIC, axis_connection += test_connection(stepperX)); + TERN_(X2_IS_TRINAMIC, axis_connection += test_connection(stepperX2)); } if (TERN0(HAS_Y_AXIS, y)) { - #if AXIS_IS_TMC(Y) - axis_connection += test_connection(stepperY); - #endif - #if AXIS_IS_TMC(Y2) - axis_connection += test_connection(stepperY2); - #endif + TERN_(Y_IS_TRINAMIC, axis_connection += test_connection(stepperY)); + TERN_(Y2_IS_TRINAMIC, axis_connection += test_connection(stepperY2)); } if (TERN0(HAS_Z_AXIS, z)) { - #if AXIS_IS_TMC(Z) - axis_connection += test_connection(stepperZ); - #endif - #if AXIS_IS_TMC(Z2) - axis_connection += test_connection(stepperZ2); - #endif - #if AXIS_IS_TMC(Z3) - axis_connection += test_connection(stepperZ3); - #endif - #if AXIS_IS_TMC(Z4) - axis_connection += test_connection(stepperZ4); - #endif + TERN_(Z_IS_TRINAMIC, axis_connection += test_connection(stepperZ)); + TERN_(Z2_IS_TRINAMIC, axis_connection += test_connection(stepperZ2)); + TERN_(Z3_IS_TRINAMIC, axis_connection += test_connection(stepperZ3)); + TERN_(Z4_IS_TRINAMIC, axis_connection += test_connection(stepperZ4)); } - #if AXIS_IS_TMC(I) - if (i) axis_connection += test_connection(stepperI); - #endif - #if AXIS_IS_TMC(J) - if (j) axis_connection += test_connection(stepperJ); - #endif - #if AXIS_IS_TMC(K) - if (k) axis_connection += test_connection(stepperK); - #endif - #if AXIS_IS_TMC(U) - if (u) axis_connection += test_connection(stepperU); - #endif - #if AXIS_IS_TMC(V) - if (v) axis_connection += test_connection(stepperV); - #endif - #if AXIS_IS_TMC(W) - if (w) axis_connection += test_connection(stepperW); - #endif + TERN_(I_IS_TRINAMIC, if (i) axis_connection += test_connection(stepperI)); + TERN_(J_IS_TRINAMIC, if (j) axis_connection += test_connection(stepperJ)); + TERN_(K_IS_TRINAMIC, if (k) axis_connection += test_connection(stepperK)); + TERN_(U_IS_TRINAMIC, if (u) axis_connection += test_connection(stepperU)); + TERN_(V_IS_TRINAMIC, if (v) axis_connection += test_connection(stepperV)); + TERN_(W_IS_TRINAMIC, if (w) axis_connection += test_connection(stepperW)); if (TERN0(HAS_EXTRUDERS, e)) { - #if AXIS_IS_TMC(E0) - axis_connection += test_connection(stepperE0); - #endif - #if AXIS_IS_TMC(E1) - axis_connection += test_connection(stepperE1); - #endif - #if AXIS_IS_TMC(E2) - axis_connection += test_connection(stepperE2); - #endif - #if AXIS_IS_TMC(E3) - axis_connection += test_connection(stepperE3); - #endif - #if AXIS_IS_TMC(E4) - axis_connection += test_connection(stepperE4); - #endif - #if AXIS_IS_TMC(E5) - axis_connection += test_connection(stepperE5); - #endif - #if AXIS_IS_TMC(E6) - axis_connection += test_connection(stepperE6); - #endif - #if AXIS_IS_TMC(E7) - axis_connection += test_connection(stepperE7); - #endif + TERN_(E0_IS_TRINAMIC, axis_connection += test_connection(stepperE0)); + TERN_(E1_IS_TRINAMIC, axis_connection += test_connection(stepperE1)); + TERN_(E2_IS_TRINAMIC, axis_connection += test_connection(stepperE2)); + TERN_(E3_IS_TRINAMIC, axis_connection += test_connection(stepperE3)); + TERN_(E4_IS_TRINAMIC, axis_connection += test_connection(stepperE4)); + TERN_(E5_IS_TRINAMIC, axis_connection += test_connection(stepperE5)); + TERN_(E6_IS_TRINAMIC, axis_connection += test_connection(stepperE6)); + TERN_(E7_IS_TRINAMIC, axis_connection += test_connection(stepperE7)); } if (axis_connection) LCD_MESSAGE(MSG_ERROR_TMC); } #endif // HAS_TRINAMIC_CONFIG - -#if HAS_TMC_SPI - #define SET_CS_PIN(st) OUT_WRITE(st##_CS_PIN, HIGH) - void tmc_init_cs_pins() { - #if AXIS_HAS_SPI(X) - SET_CS_PIN(X); - #endif - #if AXIS_HAS_SPI(Y) - SET_CS_PIN(Y); - #endif - #if AXIS_HAS_SPI(Z) - SET_CS_PIN(Z); - #endif - #if AXIS_HAS_SPI(X2) - SET_CS_PIN(X2); - #endif - #if AXIS_HAS_SPI(Y2) - SET_CS_PIN(Y2); - #endif - #if AXIS_HAS_SPI(Z2) - SET_CS_PIN(Z2); - #endif - #if AXIS_HAS_SPI(Z3) - SET_CS_PIN(Z3); - #endif - #if AXIS_HAS_SPI(Z4) - SET_CS_PIN(Z4); - #endif - #if AXIS_HAS_SPI(I) - SET_CS_PIN(I); - #endif - #if AXIS_HAS_SPI(J) - SET_CS_PIN(J); - #endif - #if AXIS_HAS_SPI(K) - SET_CS_PIN(K); - #endif - #if AXIS_HAS_SPI(U) - SET_CS_PIN(U); - #endif - #if AXIS_HAS_SPI(V) - SET_CS_PIN(V); - #endif - #if AXIS_HAS_SPI(W) - SET_CS_PIN(W); - #endif - #if AXIS_HAS_SPI(E0) - SET_CS_PIN(E0); - #endif - #if AXIS_HAS_SPI(E1) - SET_CS_PIN(E1); - #endif - #if AXIS_HAS_SPI(E2) - SET_CS_PIN(E2); - #endif - #if AXIS_HAS_SPI(E3) - SET_CS_PIN(E3); - #endif - #if AXIS_HAS_SPI(E4) - SET_CS_PIN(E4); - #endif - #if AXIS_HAS_SPI(E5) - SET_CS_PIN(E5); - #endif - #if AXIS_HAS_SPI(E6) - SET_CS_PIN(E6); - #endif - #if AXIS_HAS_SPI(E7) - SET_CS_PIN(E7); - #endif - } -#endif // HAS_TMC_SPI diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index c10bab6274..556035f08c 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -29,7 +29,7 @@ #include #include "../module/planner.h" -#define CHOPPER_DEFAULT_12V { 3, -1, 1 } +#define CHOPPER_DEFAULT_12V { 3, -1, 1 } // { toff, hend, hstrt } #define CHOPPER_DEFAULT_19V { 4, 1, 1 } #define CHOPPER_DEFAULT_24V { 4, 2, 1 } #define CHOPPER_DEFAULT_36V { 5, 2, 4 } @@ -77,8 +77,8 @@ class TMCStorage { struct { OPTCODE(HAS_STEALTHCHOP, bool stealthChop_enabled = false) - OPTCODE(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0) - OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0) + OPTCODE(HYBRID_THRESHOLD, uint16_t hybrid_thrs = 0) + OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0) } stored; }; @@ -95,7 +95,7 @@ class TMCMarlin : public TMC, public TMCStorage { TMC(CS, RS, pinMOSI, pinMISO, pinSCK) {} TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index) : - TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index) + TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index) {} uint16_t rms_current() { return TMC::rms_current(); } void rms_current(uint16_t mA) { @@ -124,7 +124,7 @@ class TMCMarlin : public TMC, public TMCStorage { #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { - return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); + return _tmc_thrs(this->microsteps(), TMC::TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); } void set_pwm_thrs(const uint32_t thrs) { TMC::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); @@ -144,15 +144,13 @@ class TMCMarlin : public TMC, public TMCStorage { #endif #endif - #if HAS_MARLINUI_MENU - void refresh_stepper_current() { rms_current(this->val_mA); } + void refresh_stepper_current() { rms_current(this->val_mA); } - #if ENABLED(HYBRID_THRESHOLD) - void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } - #endif - #if USE_SENSORLESS - void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } - #endif + #if ENABLED(HYBRID_THRESHOLD) + void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } + #endif + #if USE_SENSORLESS + void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } #endif static constexpr int8_t sgt_min = -64, @@ -199,7 +197,7 @@ class TMCMarlin : public TMC220 #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { - return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); + return _tmc_thrs(this->microsteps(), TMC2208Stepper::TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); } void set_pwm_thrs(const uint32_t thrs) { TMC2208Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); @@ -207,12 +205,10 @@ class TMCMarlin : public TMC220 } #endif - #if HAS_MARLINUI_MENU - void refresh_stepper_current() { rms_current(this->val_mA); } + void refresh_stepper_current() { rms_current(this->val_mA); } - #if ENABLED(HYBRID_THRESHOLD) - void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } - #endif + #if ENABLED(HYBRID_THRESHOLD) + void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } #endif }; @@ -253,13 +249,14 @@ class TMCMarlin : public TMC220 #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { - return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); + return _tmc_thrs(this->microsteps(), TMC2209Stepper::TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); } void set_pwm_thrs(const uint32_t thrs) { TMC2209Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); TERN_(HAS_MARLINUI_MENU, this->stored.hybrid_thrs = thrs); } #endif + #if USE_SENSORLESS int16_t homing_threshold() { return TMC2209Stepper::SGTHRS(); } void homing_threshold(int16_t sgt_val) { @@ -269,21 +266,87 @@ class TMCMarlin : public TMC220 } #endif - #if HAS_MARLINUI_MENU - void refresh_stepper_current() { rms_current(this->val_mA); } + void refresh_stepper_current() { rms_current(this->val_mA); } - #if ENABLED(HYBRID_THRESHOLD) - void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } - #endif - #if USE_SENSORLESS - void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } - #endif + #if ENABLED(HYBRID_THRESHOLD) + void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } + #endif + #if USE_SENSORLESS + void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } #endif static constexpr uint8_t sgt_min = 0, sgt_max = 255; }; +template +class TMCMarlin : public TMC2240Stepper, public TMCStorage { + public: + TMCMarlin(const uint16_t cs_pin, const uint8_t axis_chain_index) : + TMC2240Stepper(cs_pin, axis_chain_index) + {} + TMCMarlin(const uint16_t CS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index) : + TMC2240Stepper(CS, pinMOSI, pinMISO, pinSCK, axis_chain_index ) + {} + + //uint8_t get_address() { return slave_address; } + uint16_t get_microstep_counter() { return microsteps(); } + + uint16_t rms_current() { return TMC2240Stepper::rms_current(); } + void rms_current(const uint16_t mA) { + this->val_mA = mA; + TMC2240Stepper::rms_current(mA); + } + void rms_current(const uint16_t mA, const float mult) { + this->val_mA = mA; + TMC2240Stepper::rms_current(mA, mult); + } + + #if HAS_STEALTHCHOP + bool get_stealthChop() { return this->en_pwm_mode(); } + bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } + void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } + void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } + bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } + #endif + + void set_chopper_times(const chopper_timing_t &ct) { + TMC2240Stepper::toff(ct.toff); + TMC2240Stepper::hysteresis_end(ct.hend); + TMC2240Stepper::hysteresis_start(ct.hstrt); + } + + #if ENABLED(HYBRID_THRESHOLD) + uint32_t get_pwm_thrs() { + return _tmc_thrs(this->microsteps(), TMC2240Stepper::TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); + } + void set_pwm_thrs(const uint32_t thrs) { + TMC2240Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); + TERN_(HAS_MARLINUI_MENU, this->stored.hybrid_thrs = thrs); + } + #endif + + #if USE_SENSORLESS + int16_t homing_threshold() { return TMC2240Stepper::sgt(); } + void homing_threshold(int16_t sgt_val) { + sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max); + TMC2240Stepper::sgt(sgt_val); + TERN_(HAS_MARLINUI_MENU, this->stored.homing_thrs = sgt_val); + } + #endif + + void refresh_stepper_current() { rms_current(this->val_mA); } + #if ENABLED(HYBRID_THRESHOLD) + void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } + #endif + #if USE_SENSORLESS + void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } + #endif + + static constexpr int8_t sgt_min = -64, + sgt_max = 63; +}; + template class TMCMarlin : public TMC2660Stepper, public TMCStorage { public: @@ -315,12 +378,10 @@ class TMCMarlin : public TMC266 } #endif - #if HAS_MARLINUI_MENU - void refresh_stepper_current() { rms_current(this->val_mA); } + void refresh_stepper_current() { rms_current(this->val_mA); } - #if USE_SENSORLESS - void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } - #endif + #if USE_SENSORLESS + void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } #endif static constexpr int8_t sgt_min = -64, @@ -328,14 +389,14 @@ class TMCMarlin : public TMC266 }; void monitor_tmc_drivers(); -void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); +void test_tmc_connection(LOGICAL_AXIS_DECL_LC(const bool, true)); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) void tmc_set_report_interval(const uint16_t update_interval); #endif - void tmc_report_all(LOGICAL_AXIS_DECL(const bool, true)); - void tmc_get_registers(LOGICAL_AXIS_ARGS(const bool)); + void tmc_report_all(LOGICAL_AXIS_DECL_LC(const bool, true)); + void tmc_get_registers(LOGICAL_AXIS_ARGS_LC(const bool)); #endif /** @@ -348,7 +409,7 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); #if USE_SENSORLESS // Track enabled status of stealthChop and only re-enable where applicable - struct sensorless_t { bool NUM_AXIS_ARGS(), x2, y2, z2, z3, z4; }; + struct sensorless_t { bool NUM_AXIS_ARGS_() x2, y2, z2, z3, z4; }; #if ENABLED(IMPROVE_HOMING_RELIABILITY) extern millis_t sg_guard_period; @@ -361,6 +422,9 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); bool tmc_enable_stallguard(TMC2209Stepper &st); void tmc_disable_stallguard(TMC2209Stepper &st, const bool restore_stealth); + bool tmc_enable_stallguard(TMC2240Stepper &st); + void tmc_disable_stallguard(TMC2240Stepper &st, const bool restore_stealth); + bool tmc_enable_stallguard(TMC2660Stepper); void tmc_disable_stallguard(TMC2660Stepper, const bool); @@ -370,7 +434,7 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); bool TMCMarlin::test_stall_status() { this->switchCSpin(LOW); - // read stallGuard flag from TMC library, will handle HW and SW SPI + // Read stallGuard flag from TMC library, will handle HW and SW SPI TMC2130_n::DRV_STATUS_t drv_status{0}; drv_status.sr = this->DRV_STATUS(); @@ -378,12 +442,35 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); return drv_status.stallGuard; } + #endif // SPI_ENDSTOPS #endif // USE_SENSORLESS -#endif // HAS_TRINAMIC_CONFIG +#if HAS_HOMING_CURRENT -#if HAS_TMC_SPI - void tmc_init_cs_pins(); -#endif + // Axes that have a distinct homing current + struct homing_current_t { + OPTCODE(X_HAS_HOME_CURRENT, uint16_t X) + OPTCODE(Y_HAS_HOME_CURRENT, uint16_t Y) + OPTCODE(Z_HAS_HOME_CURRENT, uint16_t Z) + OPTCODE(X2_HAS_HOME_CURRENT, uint16_t X2) + OPTCODE(Y2_HAS_HOME_CURRENT, uint16_t Y2) + OPTCODE(Z2_HAS_HOME_CURRENT, uint16_t Z2) + OPTCODE(Z3_HAS_HOME_CURRENT, uint16_t Z3) + OPTCODE(Z4_HAS_HOME_CURRENT, uint16_t Z4) + OPTCODE(I_HAS_HOME_CURRENT, uint16_t I) + OPTCODE(J_HAS_HOME_CURRENT, uint16_t J) + OPTCODE(K_HAS_HOME_CURRENT, uint16_t K) + OPTCODE(U_HAS_HOME_CURRENT, uint16_t U) + OPTCODE(V_HAS_HOME_CURRENT, uint16_t V) + OPTCODE(W_HAS_HOME_CURRENT, uint16_t W) + }; + + #if ENABLED(EDITABLE_HOMING_CURRENT) + extern homing_current_t homing_current_mA; + #endif + +#endif // HAS_HOMING_CURRENT + +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/feature/tramming.cpp b/Marlin/src/feature/tramming.cpp index d03f0cf53b..3721c5eb81 100644 --- a/Marlin/src/feature/tramming.cpp +++ b/Marlin/src/feature/tramming.cpp @@ -29,31 +29,11 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" -PGMSTR(point_name_1, TRAMMING_POINT_NAME_1); -PGMSTR(point_name_2, TRAMMING_POINT_NAME_2); -PGMSTR(point_name_3, TRAMMING_POINT_NAME_3); -#ifdef TRAMMING_POINT_NAME_4 - PGMSTR(point_name_4, TRAMMING_POINT_NAME_4); - #ifdef TRAMMING_POINT_NAME_5 - PGMSTR(point_name_5, TRAMMING_POINT_NAME_5); - #ifdef TRAMMING_POINT_NAME_6 - PGMSTR(point_name_6, TRAMMING_POINT_NAME_6); - #endif - #endif -#endif +#define _TRAM_NAME_DEF(N) PGMSTR(point_name_##N, TRAMMING_POINT_NAME_##N); +#define _TRAM_NAME_ITEM(N) point_name_##N +REPEAT_1(_NR_TRAM_NAMES, _TRAM_NAME_DEF) -PGM_P const tramming_point_name[] PROGMEM = { - point_name_1, point_name_2, point_name_3 - #ifdef TRAMMING_POINT_NAME_4 - , point_name_4 - #ifdef TRAMMING_POINT_NAME_5 - , point_name_5 - #ifdef TRAMMING_POINT_NAME_6 - , point_name_6 - #endif - #endif - #endif -}; +PGM_P const tramming_point_name[] PROGMEM = { REPLIST_1(_NR_TRAM_NAMES, _TRAM_NAME_ITEM) }; #ifdef ASSISTED_TRAMMING_WAIT_POSITION diff --git a/Marlin/src/feature/tramming.h b/Marlin/src/feature/tramming.h index 925659e29d..de4c6c020c 100644 --- a/Marlin/src/feature/tramming.h +++ b/Marlin/src/feature/tramming.h @@ -24,50 +24,48 @@ #include "../inc/MarlinConfig.h" #include "../module/probe.h" -#if !WITHIN(TRAMMING_SCREW_THREAD, 30, 51) || TRAMMING_SCREW_THREAD % 10 > 1 - #error "TRAMMING_SCREW_THREAD must be equal to 30, 31, 40, 41, 50, or 51." -#endif +enum TrammingThread : uint8_t { + M3_CW = 30, M3_CCW = 31, + M4_CW = 40, M4_CCW = 41, + M5_CW = 50, M5_CCW = 51 +}; + +static_assert( + TRAMMING_SCREW_THREAD < 60 && TRAMMING_SCREW_THREAD % 10 < 2, + "TRAMMING_SCREW_THREAD must be M3_CW, M3_CCW, M4_CW, M4_CCW, M5_CW, or M5_CCW." +); constexpr xy_pos_t tramming_points[] = TRAMMING_POINT_XY; #define G35_PROBE_COUNT COUNT(tramming_points) -static_assert(WITHIN(G35_PROBE_COUNT, 3, 6), "TRAMMING_POINT_XY requires between 3 and 6 XY positions."); +static_assert(WITHIN(G35_PROBE_COUNT, 3, 9), "TRAMMING_POINT_XY requires between 3 and 9 XY positions."); -#define VALIDATE_TRAMMING_POINT(N) static_assert(N >= G35_PROBE_COUNT || Probe::build_time::can_reach(tramming_points[N]), \ - "TRAMMING_POINT_XY point " STRINGIFY(N) " is not reachable with the default NOZZLE_TO_PROBE offset and PROBING_MARGIN.") -VALIDATE_TRAMMING_POINT(0); VALIDATE_TRAMMING_POINT(1); VALIDATE_TRAMMING_POINT(2); VALIDATE_TRAMMING_POINT(3); VALIDATE_TRAMMING_POINT(4); VALIDATE_TRAMMING_POINT(5); - -extern const char point_name_1[], point_name_2[], point_name_3[] - #ifdef TRAMMING_POINT_NAME_4 - , point_name_4[] - #ifdef TRAMMING_POINT_NAME_5 - , point_name_5[] - #ifdef TRAMMING_POINT_NAME_6 - , point_name_6[] - #endif - #endif - #endif -; - -#define _NR_TRAM_NAMES 2 -#ifdef TRAMMING_POINT_NAME_3 - #undef _NR_TRAM_NAMES +#ifdef TRAMMING_POINT_NAME_9 + #define _NR_TRAM_NAMES 9 +#elif defined(TRAMMING_POINT_NAME_8) + #define _NR_TRAM_NAMES 8 +#elif defined(TRAMMING_POINT_NAME_7) + #define _NR_TRAM_NAMES 7 +#elif defined(TRAMMING_POINT_NAME_6) + #define _NR_TRAM_NAMES 6 +#elif defined(TRAMMING_POINT_NAME_5) + #define _NR_TRAM_NAMES 5 +#elif defined(TRAMMING_POINT_NAME_4) + #define _NR_TRAM_NAMES 4 +#elif defined(TRAMMING_POINT_NAME_3) #define _NR_TRAM_NAMES 3 - #ifdef TRAMMING_POINT_NAME_4 - #undef _NR_TRAM_NAMES - #define _NR_TRAM_NAMES 4 - #ifdef TRAMMING_POINT_NAME_5 - #undef _NR_TRAM_NAMES - #define _NR_TRAM_NAMES 5 - #ifdef TRAMMING_POINT_NAME_6 - #undef _NR_TRAM_NAMES - #define _NR_TRAM_NAMES 6 - #endif - #endif - #endif +#else + #define _NR_TRAM_NAMES 0 #endif + static_assert(_NR_TRAM_NAMES >= G35_PROBE_COUNT, "Define enough TRAMMING_POINT_NAME_s for all TRAMMING_POINT_XY entries."); -#undef _NR_TRAM_NAMES + +#define _TRAM_NAME_PTR(N) point_name_##N[] +extern const char REPLIST_1(_NR_TRAM_NAMES, _TRAM_NAME_PTR); + +#define _CHECK_TRAM_POINT(N) static_assert(Probe::build_time::can_reach(tramming_points[N]), "TRAMMING_POINT_XY point " STRINGIFY(N) " is not reachable with the default NOZZLE_TO_PROBE offset and PROBING_MARGIN."); +REPEAT(_NR_TRAM_NAMES, _CHECK_TRAM_POINT) +#undef _CHECK_TRAM_POINT extern PGM_P const tramming_point_name[]; diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 9aec6b0305..5cfe9f9421 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -93,8 +93,7 @@ void TWIBus::send() { // static void TWIBus::echoprefix(uint8_t bytes, FSTR_P const pref, uint8_t adr) { SERIAL_ECHO_START(); - SERIAL_ECHOF(pref); - SERIAL_ECHOPGM(": from:", adr, " bytes:", bytes, " data:"); + SERIAL_ECHO(pref, F(": from:"), adr, F(" bytes:"), bytes, F(" data:")); } // static @@ -145,7 +144,7 @@ void TWIBus::echodata(uint8_t bytes, FSTR_P const pref, uint8_t adr, const uint8 void TWIBus::echobuffer(FSTR_P const prefix, uint8_t adr) { echoprefix(buffer_s, prefix, adr); - LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); + for (uint8_t i = 0; i < buffer_s; ++i) SERIAL_CHAR(buffer[i]); SERIAL_EOL(); } diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index 806e2a147a..b438d10a33 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -64,7 +64,7 @@ class TWIBus { private: /** * @brief Number of bytes on buffer - * @description Number of bytes in the buffer waiting to be flushed to the bus + * @details Number of bytes in the buffer waiting to be flushed to the bus */ uint8_t buffer_s = 0; @@ -74,11 +74,10 @@ class TWIBus { */ uint8_t buffer[TWIBUS_BUFFER_SIZE]; - public: /** * @brief Target device address - * @description The target device address. Persists until changed. + * @details The target device address. Persists until changed. */ uint8_t addr = 0; diff --git a/Marlin/src/feature/x_twist.cpp b/Marlin/src/feature/x_twist.cpp index b5ad25cba8..6b155c49ab 100644 --- a/Marlin/src/feature/x_twist.cpp +++ b/Marlin/src/feature/x_twist.cpp @@ -30,7 +30,7 @@ XATC xatc; bool XATC::enabled; float XATC::spacing, XATC::start; -xatc_array_t XATC::z_offset; // Initialized by settings.load() +xatc_array_t XATC::z_offset; // Initialized by settings.load void XATC::reset() { constexpr float xzo[] = XATC_Z_OFFSETS; @@ -43,17 +43,17 @@ void XATC::reset() { void XATC::print_points() { SERIAL_ECHOLNPGM(" X-Twist Correction:"); - LOOP_L_N(x, XATC_MAX_POINTS) { + for (uint8_t x = 0; x < XATC_MAX_POINTS; ++x) { SERIAL_CHAR(' '); if (!isnan(z_offset[x])) serial_offset(z_offset[x]); else - LOOP_L_N(i, 6) SERIAL_CHAR(i ? '=' : ' '); + for (uint8_t i = 0; i < 6; ++i) SERIAL_CHAR(i ? '=' : ' '); } SERIAL_EOL(); } -float lerp(const_float_t t, const_float_t a, const_float_t b) { return a + t * (b - a); } +float lerp(const float t, const float a, const float b) { return a + t * (b - a); } float XATC::compensation(const xy_pos_t &raw) { if (!enabled) return 0; diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index aa6e0c1f0c..899498faae 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -58,10 +58,10 @@ * * L # Layer Layer height. (Height of nozzle above bed) If not specified .20mm will be used. * - * O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This - * is over kill, but using this parameter will let you get the very first 'circle' perfect - * so you have a trophy to peel off of the bed and hang up to show how perfectly you have your - * Mesh calibrated. If not specified, a filament length of .3mm is assumed. + * O # Ooze How much your nozzle will Ooooze filament while getting in position to print. If not + * specified, a filament length of .3mm is assumed. This might be overkill, but this + * parameter ensures the very first 'circle' is perfect (providing an ideal trophy to hang + * up to show off your perfectly calibrated Mesh). * * P # Prime Prime the nozzle with specified length of filament. If this parameter is not * given, no prime action will take place. If the parameter specifies an amount, that much @@ -102,10 +102,9 @@ #define G26_OK false #define G26_ERR true -#include "../../gcode/gcode.h" +#include "../gcode.h" #include "../../feature/bedlevel/bedlevel.h" -#include "../../MarlinCore.h" #include "../../module/planner.h" #include "../../module/motion.h" #include "../../module/tool_change.h" @@ -132,11 +131,11 @@ #endif #ifndef G26_XY_FEEDRATE - #define G26_XY_FEEDRATE (PLANNER_XY_FEEDRATE() / 3.0) + #define G26_XY_FEEDRATE (PLANNER_XY_FEEDRATE_MM_S / 3.0) #endif #ifndef G26_XY_FEEDRATE_TRAVEL - #define G26_XY_FEEDRATE_TRAVEL (PLANNER_XY_FEEDRATE() / 1.5) + #define G26_XY_FEEDRATE_TRAVEL (PLANNER_XY_FEEDRATE_MM_S / 1.5) #endif #if CROSSHAIRS_SIZE >= INTERSECTION_CIRCLE_RADIUS @@ -162,15 +161,15 @@ float g26_random_deviation = 0.0; */ bool user_canceled() { if (!ui.button_pressed()) return false; // Return if the button isn't pressed - ui.set_status(GET_TEXT_F(MSG_G26_CANCELED), 99); - TERN_(HAS_MARLINUI_MENU, ui.quick_feedback()); + LCD_MESSAGE_MAX(MSG_G26_CANCELED); + ui.quick_feedback(); ui.wait_for_release(); return true; } #endif -void move_to(const_float_t rx, const_float_t ry, const_float_t z, const_float_t e_delta) { +void move_to(const float rx, const float ry, const float z, const float e_delta) { static float last_z = -999.99; const xy_pos_t dest = { rx, ry }; @@ -196,7 +195,7 @@ void move_to(const_float_t rx, const_float_t ry, const_float_t z, const_float_t prepare_internal_move_to_destination(fr_mm_s); } -void move_to(const xyz_pos_t &where, const_float_t de) { move_to(where.x, where.y, where.z, de); } +void move_to(const xyz_pos_t &where, const float de) { move_to(where.x, where.y, where.z, de); } typedef struct { float extrusion_multiplier = EXTRUSION_MULTIPLIER, @@ -268,8 +267,10 @@ typedef struct { // If the end point of the line is closer to the nozzle, flip the direction, // moving from the end to the start. On very small lines the optimization isn't worth it. - if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length)) - return print_line_from_here_to_there(e, s); + if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length)) { + print_line_from_here_to_there(e, s); + return; + } // Decide whether to retract & lift if (dist_start > 2.0) retract_lift_move(s); @@ -321,11 +322,9 @@ typedef struct { #if HAS_HEATED_BED if (bed_temp > 25) { - #if HAS_WIRED_LCD - ui.set_status(GET_TEXT_F(MSG_G26_HEATING_BED), 99); - ui.quick_feedback(); - TERN_(HAS_MARLINUI_MENU, ui.capture()); - #endif + LCD_MESSAGE_MAX(MSG_G26_HEATING_BED); + ui.quick_feedback(); + TERN_(HAS_MARLINUI_MENU, ui.capture()); thermalManager.setTargetBed(bed_temp); // Wait for the temperature to stabilize @@ -340,20 +339,16 @@ typedef struct { #endif // HAS_HEATED_BED // Start heating the active nozzle - #if HAS_WIRED_LCD - ui.set_status(GET_TEXT_F(MSG_G26_HEATING_NOZZLE), 99); - ui.quick_feedback(); - #endif + LCD_MESSAGE_MAX(MSG_G26_HEATING_NOZZLE); + ui.quick_feedback(); thermalManager.setTargetHotend(hotend_temp, active_extruder); // Wait for the temperature to stabilize if (!thermalManager.wait_for_hotend(active_extruder, true OPTARG(G26_CLICK_CAN_CANCEL, true))) return G26_ERR; - #if HAS_WIRED_LCD - ui.reset_status(); - ui.quick_feedback(); - #endif + ui.reset_status(); + ui.completion_feedback(); return G26_OK; } @@ -371,7 +366,7 @@ typedef struct { if (prime_flag == -1) { // The user wants to control how much filament gets purged ui.capture(); - ui.set_status(GET_TEXT_F(MSG_G26_MANUAL_PRIME), 99); + LCD_MESSAGE_MAX(MSG_G26_MANUAL_PRIME); ui.chirp(); destination = current_position; @@ -398,17 +393,15 @@ typedef struct { ui.wait_for_release(); - ui.set_status(GET_TEXT_F(MSG_G26_PRIME_DONE), 99); + LCD_MESSAGE_MAX(MSG_G26_PRIME_DONE); ui.quick_feedback(); ui.release(); } else #endif { - #if HAS_WIRED_LCD - ui.set_status(GET_TEXT_F(MSG_G26_FIXED_LENGTH), 99); - ui.quick_feedback(); - #endif + LCD_MESSAGE_MAX(MSG_G26_FIXED_LENGTH); + ui.quick_feedback(); destination = current_position; destination.e += prime_length; prepare_internal_move_to_destination(fr_slow_e); @@ -509,8 +502,10 @@ void GcodeSuite::G26() { // or if the parameter parsing did not go OK, abort if (homing_needed_error()) return; - // Change the tool first, if specified - if (parser.seenval('T')) tool_change(parser.value_int()); + #if HAS_TOOLCHANGE + // Change the tool first, if specified + if (parser.seenval('T')) tool_change(parser.value_int()); + #endif g26_helper_t g26; @@ -538,7 +533,7 @@ void GcodeSuite::G26() { if (bedtemp) { if (!WITHIN(bedtemp, 40, BED_MAX_TARGET)) { - SERIAL_ECHOLNPGM("?Specified bed temperature not plausible (40-", BED_MAX_TARGET, "C)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Specified bed temperature not plausible (40-", BED_MAX_TARGET, "C).")); return; } g26.bed_temp = bedtemp; @@ -549,7 +544,7 @@ void GcodeSuite::G26() { if (parser.seenval('L')) { g26.layer_height = parser.value_linear_units(); if (!WITHIN(g26.layer_height, 0.0, 2.0)) { - SERIAL_ECHOLNPGM("?Specified layer height not plausible."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Specified layer height not plausible.")); return; } } @@ -558,12 +553,12 @@ void GcodeSuite::G26() { if (parser.has_value()) { g26.retraction_multiplier = parser.value_float(); if (!WITHIN(g26.retraction_multiplier, 0.05, 15.0)) { - SERIAL_ECHOLNPGM("?Specified Retraction Multiplier not plausible."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Specified Retraction Multiplier not plausible.")); return; } } else { - SERIAL_ECHOLNPGM("?Retraction Multiplier must be specified."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Retraction Multiplier must be specified.")); return; } } @@ -571,7 +566,7 @@ void GcodeSuite::G26() { if (parser.seenval('S')) { g26.nozzle = parser.value_float(); if (!WITHIN(g26.nozzle, 0.1, 2.0)) { - SERIAL_ECHOLNPGM("?Specified nozzle size not plausible."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Specified nozzle size not plausible.")); return; } } @@ -581,7 +576,7 @@ void GcodeSuite::G26() { #if HAS_MARLINUI_MENU g26.prime_flag = -1; #else - SERIAL_ECHOLNPGM("?Prime length must be specified when not using an LCD."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Prime length must be specified when not using an LCD.")); return; #endif } @@ -589,7 +584,7 @@ void GcodeSuite::G26() { g26.prime_flag++; g26.prime_length = parser.value_linear_units(); if (!WITHIN(g26.prime_length, 0.0, 25.0)) { - SERIAL_ECHOLNPGM("?Specified prime length not plausible."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Specified prime length not plausible.")); return; } } @@ -598,7 +593,7 @@ void GcodeSuite::G26() { if (parser.seenval('F')) { g26.filament_diameter = parser.value_linear_units(); if (!WITHIN(g26.filament_diameter, 1.0, 4.0)) { - SERIAL_ECHOLNPGM("?Specified filament size not plausible."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Specified filament size not plausible.")); return; } } @@ -621,8 +616,8 @@ void GcodeSuite::G26() { // If any preset or temperature was specified if (noztemp) { - if (!WITHIN(noztemp, 165, (HEATER_0_MAXTEMP) - (HOTEND_OVERSHOOT))) { - SERIAL_ECHOLNPGM("?Specified nozzle temperature not plausible."); + if (!WITHIN(noztemp, 165, thermalManager.hotend_max_target(active_extruder))) { + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Specified nozzle temperature not plausible.")); return; } g26.hotend_temp = noztemp; @@ -636,19 +631,19 @@ void GcodeSuite::G26() { } // Get repeat from 'R', otherwise do one full circuit - int16_t g26_repeats; + grid_count_t g26_repeats; #if HAS_MARLINUI_MENU g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1); #else if (parser.seen('R')) g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; else { - SERIAL_ECHOLNPGM("?(R)epeat must be specified when not using an LCD."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(R)epeat must be specified when not using an LCD.")); return; } #endif if (g26_repeats < 1) { - SERIAL_ECHOLNPGM("?(R)epeat value not plausible; must be at least 1."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(R)epeat value not plausible; must be at least 1.")); return; } @@ -656,7 +651,7 @@ void GcodeSuite::G26() { g26.xy_pos.set(parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : current_position.x, parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : current_position.y); if (!position_is_reachable(g26.xy_pos)) { - SERIAL_ECHOLNPGM("?Specified X,Y coordinate out of bounds."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Specified X,Y coordinate out of bounds.")); return; } @@ -667,7 +662,7 @@ void GcodeSuite::G26() { do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION bool volumetric_was_enabled = parser.volumetric_enabled; parser.volumetric_enabled = false; planner.calculate_volumetric_multipliers(); @@ -715,7 +710,7 @@ void GcodeSuite::G26() { #error "A_CNT must be a positive value. Please change A_INT." #endif float trig_table[A_CNT]; - LOOP_L_N(i, A_CNT) + for (uint8_t i = 0; i < A_CNT; ++i) trig_table[i] = INTERSECTION_CIRCLE_RADIUS * cos(RADIANS(i * A_INT)); #endif // !ARC_SUPPORT @@ -789,7 +784,7 @@ void GcodeSuite::G26() { g26.recover_filament(destination); - { REMEMBER(fr, feedrate_mm_s, PLANNER_XY_FEEDRATE() * 0.1f); + { REMEMBER(fr, feedrate_mm_s, PLANNER_XY_FEEDRATE_MM_S * 0.1f); plan_arc(endpoint, arc_offset, false, 0); // Draw a counter-clockwise arc destination = current_position; } @@ -853,14 +848,14 @@ void GcodeSuite::G26() { } while (--g26_repeats && location.valid()); LEAVE: - ui.set_status(GET_TEXT_F(MSG_G26_LEAVING), -1); + LCD_MESSAGE_MIN(MSG_G26_LEAVING); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, ExtUI::G26_FINISH)); g26.retract_filament(destination); destination.z = Z_CLEARANCE_BETWEEN_PROBES; move_to(destination, 0); // Raise the nozzle - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION parser.volumetric_enabled = volumetric_was_enabled; planner.calculate_volumetric_multipliers(); #endif diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index dd828bf0c8..b3c56b49b3 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -29,10 +29,6 @@ #include "../../module/probe.h" #include "../../feature/bedlevel/bedlevel.h" -#if HAS_MULTI_HOTEND - #include "../../module/tool_change.h" -#endif - #if ENABLED(BLTOUCH) #include "../../feature/bltouch.h" #endif @@ -57,8 +53,9 @@ * 41 - Counter-Clockwise M4 * 50 - Clockwise M5 * 51 - Counter-Clockwise M5 - **/ + */ void GcodeSuite::G35() { + DEBUG_SECTION(log_G35, "G35", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); @@ -67,7 +64,7 @@ void GcodeSuite::G35() { const uint8_t screw_thread = parser.byteval('S', TRAMMING_SCREW_THREAD); if (!WITHIN(screw_thread, 30, 51) || screw_thread % 10 > 1) { - SERIAL_ECHOLNPGM("?(S)crew thread must be 30, 31, 40, 41, 50, or 51."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(S)crew thread must be 30, 31, 40, 41, 50, or 51.")); return; } @@ -82,15 +79,9 @@ void GcodeSuite::G35() { set_bed_leveling_enabled(false); #endif - #if ENABLED(CNC_WORKSPACE_PLANES) - workspace_plane = PLANE_XY; - #endif + TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); - // Always home with tool 0 active - #if HAS_MULTI_HOTEND - const uint8_t old_tool_index = active_extruder; - tool_change(0, true); - #endif + probe.use_probing_tool(); // Disable duplication mode on homing TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); @@ -101,30 +92,25 @@ void GcodeSuite::G35() { bool err_break = false; // Probe all positions - LOOP_L_N(i, G35_PROBE_COUNT) { - - // In BLTOUCH HS mode, the probe travels in a deployed state. - // Users of G35 might have a badly misaligned bed, so raise Z by the - // length of the deployed pin (BLTOUCH stroke < 7mm) - - // Unsure if this is even required. The probe seems to lift correctly after probe done. - do_blocking_move_to_z(SUM_TERN(BLTOUCH, Z_CLEARANCE_BETWEEN_PROBES, bltouch.z_extra_clearance())); - const float z_probed_height = probe.probe_at_point(tramming_points[i], PROBE_PT_RAISE, 0, true); - + for (uint8_t i = 0; i < G35_PROBE_COUNT; ++i) { + const float z_probed_height = probe.probe_at_point(tramming_points[i], PROBE_PT_RAISE); if (isnan(z_probed_height)) { - SERIAL_ECHOPGM("G35 failed at point ", i + 1, " ("); - SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); - SERIAL_CHAR(')'); - SERIAL_ECHOLNPGM_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y); + SERIAL_ECHOLN( + F("G35 failed at point "), i + 1, + F(" ("), FPSTR(pgm_read_ptr(&tramming_point_name[i])), C(')'), + FPSTR(SP_X_STR), tramming_points[i].x, + FPSTR(SP_Y_STR), tramming_points[i].y + ); err_break = true; break; } if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPGM("Probing point ", i + 1, " ("); - DEBUG_ECHOF(FPSTR(pgm_read_ptr(&tramming_point_name[i]))); - DEBUG_CHAR(')'); - DEBUG_ECHOLNPGM_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y, SP_Z_STR, z_probed_height); + DEBUG_ECHOLN( + F("Probing point "), i + 1, F(" ("), FPSTR(pgm_read_ptr(&tramming_point_name[i])), C(')'), + FPSTR(SP_X_STR), tramming_points[i].x, FPSTR(SP_Y_STR), tramming_points[i].y, + FPSTR(SP_Z_STR), z_probed_height + ); } z_measured[i] = z_probed_height; @@ -134,7 +120,7 @@ void GcodeSuite::G35() { const float threads_factor[] = { 0.5, 0.7, 0.8 }; // Calculate adjusts - LOOP_S_L_N(i, 1, G35_PROBE_COUNT) { + for (uint8_t i = 1; i < G35_PROBE_COUNT; ++i) { const float diff = z_measured[0] - z_measured[i], adjust = ABS(diff) < 0.001f ? 0 : diff / threads_factor[(screw_thread - 30) / 10]; @@ -154,11 +140,9 @@ void GcodeSuite::G35() { SERIAL_ECHOLNPGM("G35 aborted."); // Restore the active tool after homing - #if HAS_MULTI_HOTEND - if (old_tool_index != 0) tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous toolhead if not PARKING_EXTRUDER - #endif + probe.use_probing_tool(false); - #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35) + #if ALL(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35) set_bed_leveling_enabled(leveling_was_active); #endif diff --git a/Marlin/src/gcode/bedlevel/G42.cpp b/Marlin/src/gcode/bedlevel/G42.cpp index cb5ed97406..4b9b028419 100644 --- a/Marlin/src/gcode/bedlevel/G42.cpp +++ b/Marlin/src/gcode/bedlevel/G42.cpp @@ -25,49 +25,57 @@ #if HAS_MESH #include "../gcode.h" -#include "../../MarlinCore.h" // for IsRunning() #include "../../module/motion.h" -#include "../../module/probe.h" // for probe.offset #include "../../feature/bedlevel/bedlevel.h" +#if HAS_PROBE_XY_OFFSET + #include "../../module/probe.h" // for probe.offset +#endif + /** * G42: Move X & Y axes to mesh coordinates (I & J) + * + * Parameters: + * F : Feedrate in mm/min + * I : X axis point index + * J : Y axis point index + * P : Flag to put the probe at the given point */ void GcodeSuite::G42() { - if (MOTION_CONDITIONS) { - const bool hasI = parser.seenval('I'); - const int8_t ix = hasI ? parser.value_int() : 0; - const bool hasJ = parser.seenval('J'); - const int8_t iy = hasJ ? parser.value_int() : 0; + if (!MOTION_CONDITIONS) return; - if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) { - SERIAL_ECHOLNPGM(STR_ERR_MESH_XY); - return; - } + const bool hasI = parser.seenval('I'); + const int8_t ix = hasI ? parser.value_int() : 0; + const bool hasJ = parser.seenval('J'); + const int8_t iy = hasJ ? parser.value_int() : 0; - // Move to current_position, as modified by I, J, P parameters - destination = current_position; - - 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')) { - if (hasI) destination.x -= probe.offset_xy.x; - if (hasJ) destination.y -= probe.offset_xy.y; - } - #endif - - const feedRate_t fval = parser.linearval('F'), - fr_mm_s = MMM_TO_MMS(fval > 0 ? fval : 0.0f); - - // SCARA kinematic has "safe" XY raw moves - #if IS_SCARA - prepare_internal_fast_move_to_destination(fr_mm_s); - #else - prepare_internal_move_to_destination(fr_mm_s); - #endif + if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) { + SERIAL_ECHOLNPGM(STR_ERR_MESH_XY); + return; } + + // Move to current_position, as modified by I, J, P parameters + destination = current_position; + + 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.seen_test('P')) { + if (hasI) destination.x -= probe.offset_xy.x; + if (hasJ) destination.y -= probe.offset_xy.y; + } + #endif + + const feedRate_t fval = parser.linearval('F'), + fr_mm_s = MMM_TO_MMS(fval > 0 ? fval : 0.0f); + + // SCARA kinematic has "safe" XY raw moves + #if IS_SCARA + prepare_internal_fast_move_to_destination(fr_mm_s); + #else + prepare_internal_move_to_destination(fr_mm_s); + #endif } #endif // HAS_MESH diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 277f95b9ff..05fa98e459 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -27,7 +27,10 @@ #include "../gcode.h" #include "../../feature/bedlevel/bedlevel.h" #include "../../module/planner.h" -#include "../../module/probe.h" + +#if ENABLED(MARLIN_DEV_MODE) + #include "../../module/probe.h" +#endif #if ENABLED(EEPROM_SETTINGS) #include "../../module/settings.h" @@ -42,14 +45,14 @@ /** * M420: Enable/Disable Bed Leveling and/or set the Z fade height. * - * S[bool] Turns leveling on or off - * Z[height] Sets the Z fade height (0 or none to disable) - * V[bool] Verbose - Print the leveling grid + * S Turns leveling on or off + * Z Sets the Z fade height (0 or none to disable) + * V Verbose - Print the leveling grid * * With AUTO_BED_LEVELING_UBL only: * - * L[index] Load UBL mesh from index (0 is default) - * T[map] 0:Human-readable 1:CSV 2:"LCD" 4:Compact + * L Load UBL mesh from index (0 is default) + * T 0:Human-readable 1:CSV 2:"LCD" 4:Compact * * With mesh-based leveling only: * @@ -105,13 +108,12 @@ void GcodeSuite::M420() { const int16_t a = settings.calc_num_meshes(); if (!a) { - SERIAL_ECHOLNPGM("?EEPROM storage not available."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("EEPROM storage not available.")); return; } if (!WITHIN(storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPGM("?Invalid storage slot."); - SERIAL_ECHOLNPGM("?Use 0 to ", a - 1); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Invalid storage slot. Use 0 to ", a - 1)); return; } @@ -120,7 +122,7 @@ void GcodeSuite::M420() { #else - SERIAL_ECHOLNPGM("?EEPROM storage not available."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("EEPROM storage not available.")); return; #endif @@ -226,9 +228,7 @@ void GcodeSuite::M420() { if (to_enable && !planner.leveling_active) SERIAL_ERROR_MSG(STR_ERR_M420_FAILED); - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Bed Leveling "); - serialprintln_onoff(planner.leveling_active); + SERIAL_ECHO_MSG("Bed Leveling ", ON_OFF(planner.leveling_active)); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_ECHO_START(); @@ -245,17 +245,18 @@ void GcodeSuite::M420() { } void GcodeSuite::M420_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F( TERN(MESH_BED_LEVELING, "Mesh Bed Leveling", TERN(AUTO_BED_LEVELING_UBL, "Unified Bed Leveling", "Auto Bed Leveling")) )); - SERIAL_ECHOF( + SERIAL_ECHOLN( F(" M420 S"), planner.leveling_active #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) , FPSTR(SP_Z_STR), LINEAR_UNIT(planner.z_fade_height) #endif - , F(" ; Leveling ") + , F(" ; Leveling "), ON_OFF(planner.leveling_active) ); - serialprintln_onoff(planner.leveling_active); } #endif // HAS_LEVELING diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 0fef5ad683..800d51dac6 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -33,6 +33,7 @@ #include "../../../module/motion.h" #include "../../../module/planner.h" #include "../../../module/probe.h" +#include "../../../module/temperature.h" #include "../../queue.h" #if ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -42,23 +43,26 @@ #if ABL_PLANAR #include "../../../libs/vector_3.h" #endif +#if ENABLED(BD_SENSOR_PROBE_NO_STOP) + #include "../../../feature/bedlevel/bdl/bdl.h" +#endif #include "../../../lcd/marlinui.h" #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD) - #include "../../../lcd/e3v2/creality/dwin.h" -#elif ENABLED(DWIN_LCD_PROUI) - #include "../../../lcd/e3v2/proui/dwin.h" -#endif - -#if HAS_MULTI_HOTEND - #include "../../../module/tool_change.h" + #include "../../../lcd/dwin/creality/dwin.h" +#elif ENABLED(SOVOL_SV06_RTS) + #include "../../../lcd/sovol_rts/sovol_rts.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../../core/debug_out.h" +#if DISABLED(PROBE_MANUALLY) && ENABLED(FT_MOTION) + #include "../../../module/ft_motion.h" +#endif + #if ABL_USES_GRID #if ENABLED(PROBE_Y_FIRST) #define PR_OUTER_VAR abl.meshCount.x @@ -73,14 +77,21 @@ #endif #endif +/** + * @brief Do some things before returning from G29. + * @param retry : true if the G29 can and should be retried. false if the failure is too serious. + * @param did : true if the leveling procedure completed successfully. + */ 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()); - } + #if DISABLED(G29_RETRY_AND_RECOVER) + if (!retry || did) { + TERN_(DWIN_CREALITY_LCD, dwinLevelingDone()); + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); + } + #endif } #define G29_RETURN(retry, did) do{ \ @@ -97,20 +108,16 @@ public: bool dryrun, reenable; - #if HAS_MULTI_HOTEND - uint8_t tool_index; - #endif - - #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) + #if ANY(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) int abl_probe_index; #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) - int abl_points; + grid_count_t abl_points; #elif ENABLED(AUTO_BED_LEVELING_3POINT) - static constexpr int abl_points = 3; + static constexpr grid_count_t abl_points = 3; #elif ABL_USES_GRID - static constexpr int abl_points = GRID_MAX_POINTS; + static constexpr grid_count_t abl_points = GRID_MAX_POINTS; #endif #if ABL_USES_GRID @@ -136,96 +143,88 @@ public: #if ENABLED(AUTO_BED_LEVELING_LINEAR) int indexIntoAB[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; - float eqnAMatrix[(GRID_MAX_POINTS) * 3], // "A" matrix of the linear system of equations - eqnBVector[GRID_MAX_POINTS], // "B" vector of Z points + float eqnAMatrix[GRID_MAX_POINTS * 3], // "A" matrix of the linear system of equations + eqnBVector[GRID_MAX_POINTS], // "B" vector of Z points mean; #endif #endif }; -#if ABL_USES_GRID && EITHER(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR) +#if ABL_USES_GRID && ANY(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR) constexpr xy_uint8_t G29_State::grid_points; - constexpr int G29_State::abl_points; + constexpr grid_count_t G29_State::abl_points; #endif /** - * G29: Detailed Z probe, probes the bed at 3 or more points. - * Will fail if the printer has not been homed with G28. + * G29: Bed Leveling * - * Enhanced G29 Auto Bed Leveling Probe Routine + * Enhanced G29 Auto Bed Leveling Probe Routine. + * Probes the bed at 3 or more points. + * Will fail if the printer has not been homed with G28. * - * O Auto-level only if needed + * Parameters: + * O Auto-level only if needed (Optional) * - * D Dry-Run mode. Just evaluate the bed Topology - Don't apply - * or alter the bed level data. Useful to check the topology - * after a first run of G29. + * D Dry-Run mode. Just evaluate the bed Topology - + * Don't apply or alter the bed level data. + * Useful to check the topology after a first run of G29. * - * J Jettison current bed leveling data + * J Jettison current bed leveling data * - * V Set the verbose level (0-4). Example: "G29 V3" + * V<0-4> Set the verbose level (0-4) + * Example: G29 V3 * - * Parameters With LINEAR leveling only: + * With AUTO_BED_LEVELING_LINEAR: + * P Set the size of the grid that will be probed (P x P points) + * Example: G29 P4 * - * P Set the size of the grid that will be probed (P x P points). - * Example: "G29 P4" + * X Set the X size of the grid that will be probed (X x Y points) + * Example: G29 X7 Y5 * - * X Set the X size of the grid that will be probed (X x Y points). - * Example: "G29 X7 Y5" + * Y Set the Y size of the grid that will be probed (X x Y points) * - * Y Set the Y size of the grid that will be probed (X x Y points). + * T Generate a Bed Topology Report + * Example: G29 P5 T - for a detailed report. + * This is useful for manual bed leveling and finding flaws in the bed + * (to assist with part placement). + * Not supported by non-linear delta printer bed leveling. * - * T Generate a Bed Topology Report. Example: "G29 P5 T" for a detailed report. - * This is useful for manual bed leveling and finding flaws in the bed (to - * assist with part placement). - * Not supported by non-linear delta printer bed leveling. + * With AUTO_BED_LEVELING_LINEAR and AUTO_BED_LEVELING_BILINEAR: + * S Set the XY travel speed between probe points (in units/min) + * H Set bounds to a centered square H x H units in size + * -or- + * F Set the Front limit of the probing grid + * B Set the Back limit of the probing grid + * L Set the Left limit of the probing grid + * R Set the Right limit of the probing grid * - * Parameters With LINEAR and BILINEAR leveling only: + * With AUTO_BED_LEVELING_BILINEAR: + * Z Supply additional Z offset to all probe points. + * W Write a mesh point. (If G29 is idle.) + * I Index for mesh point + * J Index for mesh point + * X For mesh point, overrides I + * Y For mesh point, overrides J + * Z For mesh point. If omitted, uses current position's raw Z * - * S Set the XY travel speed between probe points (in units/min) + * With DEBUG_LEVELING_FEATURE: + * C Make a totally fake grid with no actual probing. + * For use in testing when no probing is possible. * - * H Set bounds to a centered square H x H units in size + * With PROBE_MANUALLY: + * To do manual probing simply repeat G29 until the procedure is complete. + * The first G29 accepts parameters. 'G29 Q' for status, 'G29 A' to abort. * - * -or- + * Q Query leveling and G29 state + * A Abort current leveling procedure * - * F Set the Front limit of the probing grid - * B Set the Back limit of the probing grid - * L Set the Left limit of the probing grid - * R Set the Right limit of the probing grid - * - * Parameters with DEBUG_LEVELING_FEATURE only: - * - * C Make a totally fake grid with no actual probing. - * For use in testing when no probing is possible. - * - * Parameters with BILINEAR leveling only: - * - * Z Supply an additional Z probe offset - * - * Extra parameters with PROBE_MANUALLY: - * - * To do manual probing simply repeat G29 until the procedure is complete. - * The first G29 accepts parameters. 'G29 Q' for status, 'G29 A' to abort. - * - * Q Query leveling and G29 state - * - * A Abort current leveling procedure - * - * Extra parameters with BILINEAR only: - * - * W Write a mesh point. (If G29 is idle.) - * I X index for mesh point - * J Y index for mesh point - * X X for mesh point, overrides I - * Y Y for mesh point, overrides J - * Z Z for mesh point. Otherwise, raw current Z. - * - * Without PROBE_MANUALLY: - * - * E By default G29 will engage the Z probe, test the bed, then disengage. - * Include "E" to engage/disengage the Z probe for each sample. - * There's no extra effect if you have a fixed Z probe. + * Without PROBE_MANUALLY: + * E By default G29 will engage the Z probe, test the bed, then disengage + * Include "E" to engage/disengage the Z probe for each sample. + * There's no extra effect if you have a fixed Z probe. */ G29_TYPE GcodeSuite::G29() { + DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING)); // Leveling state is persistent when done manually with multiple G29 commands @@ -235,7 +234,7 @@ G29_TYPE GcodeSuite::G29() { reset_stepper_timeout(); // Q = Query leveling and G29 state - const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); + const bool seenQ = ANY(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); // G29 Q is also available if debugging #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -276,17 +275,24 @@ G29_TYPE GcodeSuite::G29() { // Set and report "probing" state to host TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE, false)); + #if DISABLED(PROBE_MANUALLY) + // Potentially disable Fixed-Time Motion for probing + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); + #endif + /** * On the initial G29 fetch command parameters. */ if (!g29_in_progress) { - #if HAS_MULTI_HOTEND - abl.tool_index = active_extruder; - if (active_extruder != 0) tool_change(0, true); + probe.use_probing_tool(); + + #ifdef EVENT_GCODE_BEFORE_G29 + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Before G29 G-code: ", EVENT_GCODE_BEFORE_G29); + gcode.process_subcommands_now(F(EVENT_GCODE_BEFORE_G29)); #endif - #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) + #if ANY(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) abl.abl_probe_index = -1; #endif @@ -351,7 +357,7 @@ G29_TYPE GcodeSuite::G29() { abl.verbose_level = parser.intval('V'); if (!WITHIN(abl.verbose_level, 0, 4)) { - SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(V)erbose level implausible (0-4).")); G29_RETURN(false, false); } @@ -372,11 +378,11 @@ G29_TYPE GcodeSuite::G29() { if (parser.seenval('P')) abl.grid_points.x = abl.grid_points.y = parser.value_int(); if (!WITHIN(abl.grid_points.x, 2, GRID_MAX_POINTS_X)) { - SERIAL_ECHOLNPGM("?Probe points (X) implausible (2-" STRINGIFY(GRID_MAX_POINTS_X) ")."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Probe points (X) implausible (2-" STRINGIFY(GRID_MAX_POINTS_X) ").")); G29_RETURN(false, false); } if (!WITHIN(abl.grid_points.y, 2, GRID_MAX_POINTS_Y)) { - SERIAL_ECHOLNPGM("?Probe points (Y) implausible (2-" STRINGIFY(GRID_MAX_POINTS_Y) ")."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Probe points (Y) implausible (2-" STRINGIFY(GRID_MAX_POINTS_Y) ").")); G29_RETURN(false, false); } @@ -391,7 +397,12 @@ G29_TYPE GcodeSuite::G29() { #if ABL_USES_GRID + constexpr feedRate_t min_probe_feedrate_mm_s = XY_PROBE_FEEDRATE_MIN; xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.linearval('S', XY_PROBE_FEEDRATE)); + if (xy_probe_feedrate_mm_s < min_probe_feedrate_mm_s) { + xy_probe_feedrate_mm_s = min_probe_feedrate_mm_s; + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Feedrate (S) too low. (Using ", min_probe_feedrate_mm_s, ")")); + } const float x_min = probe.min_x(), x_max = probe.max_x(), y_min = probe.min_y(), y_max = probe.max_y(); @@ -409,15 +420,15 @@ G29_TYPE GcodeSuite::G29() { if (!probe.good_bounds(abl.probe_position_lf, abl.probe_position_rb)) { if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPGM("G29 L", abl.probe_position_lf.x, " R", abl.probe_position_rb.x, - " F", abl.probe_position_lf.y, " B", abl.probe_position_rb.y); + " F", abl.probe_position_lf.y, " B", abl.probe_position_rb.y); } - SERIAL_ECHOLNPGM("? (L,R,F,B) out of bounds."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG(" (L,R,F,B) out of bounds.")); G29_RETURN(false, false); } // Probe at the points of a lattice grid abl.gridSpacing.set((abl.probe_position_rb.x - abl.probe_position_lf.x) / (abl.grid_points.x - 1), - (abl.probe_position_rb.y - abl.probe_position_lf.y) / (abl.grid_points.y - 1)); + (abl.probe_position_rb.y - abl.probe_position_lf.y) / (abl.grid_points.y - 1)); #endif // ABL_USES_GRID @@ -432,8 +443,6 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(AUTO_BED_LEVELING_3POINT) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> 3-point Leveling"); points[0].z = points[1].z = points[2].z = 0; // Probe at 3 arbitrary points - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart()); #endif TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); @@ -442,20 +451,20 @@ G29_TYPE GcodeSuite::G29() { remember_feedrate_scaling_off(); #if ENABLED(PREHEAT_BEFORE_LEVELING) + #if ENABLED(SOVOL_SV06_RTS) + rts.updateTempE0(); + rts.updateTempBed(); + rts.sendData(1, Wait_VP); + rts.gotoPage(ID_ABL_HeatWait_L, ID_ABL_HeatWait_D); + #endif if (!abl.dryrun) probe.preheat_for_probing(LEVELING_NOZZLE_TEMP, - #if BOTH(DWIN_LCD_PROUI, HAS_HEATED_BED) - HMI_data.BedLevT - #else - LEVELING_BED_TEMP - #endif + TERN(EXTENSIBLE_UI, ExtUI::getLevelingBedTemp(), LEVELING_BED_TEMP) ); #endif } // Position bed horizontally and Z probe vertically. - #if defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \ - || defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \ - || defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W) + #if HAS_SAFE_BED_LEVELING xyze_pos_t safe_position = current_position; #ifdef SAFE_BED_LEVELING_START_X safe_position.x = SAFE_BED_LEVELING_START_X; @@ -486,14 +495,14 @@ G29_TYPE GcodeSuite::G29() { #endif do_blocking_move_to(safe_position); - #endif + #endif // HAS_SAFE_BED_LEVELING // Disable auto bed leveling during G29. // Be formal so G29 can be done successively without G28. if (!no_action) set_bed_leveling_enabled(false); // Deploy certain probes before starting probing - #if ENABLED(BLTOUCH) + #if ENABLED(BLTOUCH) || ALL(HAS_Z_SERVO_PROBE, Z_SERVO_INTERMEDIATE_STOW) do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE); #elif HAS_BED_PROBE if (probe.deploy()) { // (returns true on deploy failure) @@ -503,20 +512,13 @@ G29_TYPE GcodeSuite::G29() { #endif #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (!abl.dryrun - && (abl.gridSpacing != bedlevel.grid_spacing || abl.probe_position_lf != bedlevel.grid_start) - ) { - // Reset grid to 0.0 or "not probed". (Also disables ABL) - reset_bed_level(); - - // Can't re-enable (on error) until the new grid is written - abl.reenable = false; + if (!abl.dryrun && (abl.gridSpacing != bedlevel.grid_spacing || abl.probe_position_lf != bedlevel.grid_start)) { + reset_bed_level(); // Reset grid to 0.0 or "not probed". (Also disables ABL) + abl.reenable = false; // Can't re-enable (on error) until the new grid is written } - // Pre-populate local Z values from the stored mesh TERN_(IS_KINEMATIC, COPY(abl.z_values, bedlevel.z_values)); - - #endif // AUTO_BED_LEVELING_BILINEAR + #endif } // !g29_in_progress @@ -558,7 +560,7 @@ G29_TYPE GcodeSuite::G29() { } else { - #if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) + #if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) const uint16_t index = abl.abl_probe_index - 1; #endif @@ -690,10 +692,10 @@ G29_TYPE GcodeSuite::G29() { inInc = -1; // Zag left } - zig ^= true; // zag + FLIP(zig); // zag // An index to print current state - uint8_t pt_index = (PR_OUTER_VAR) * (PR_INNER_SIZE) + 1; + grid_count_t pt_index = (PR_OUTER_VAR) * (PR_INNER_SIZE) + 1; // Inner loop is Y with PROBE_Y_FIRST enabled // Inner loop is X with PROBE_Y_FIRST disabled @@ -709,7 +711,67 @@ G29_TYPE GcodeSuite::G29() { if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing mesh point ", pt_index, "/", abl.abl_points, "."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points))); - abl.measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); + #if ENABLED(BD_SENSOR_PROBE_NO_STOP) + if (PR_INNER_VAR == inStart) { + char tmp_1[32]; + + // move to the start point of new line + abl.measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); + // Go to the end of the row/column ... and back up by one + // TODO: Why not just use... PR_INNER_VAR = inStop - inInc + for (PR_INNER_VAR = inStart; PR_INNER_VAR != inStop; PR_INNER_VAR += inInc); + PR_INNER_VAR -= inInc; + + // Get the coordinate of the resulting grid point + abl.probePos = abl.probe_position_lf + abl.gridSpacing * abl.meshCount.asFloat(); + + // Coordinate that puts the probe at the grid point + abl.probePos -= probe.offset_xy; + + // Put a G1 move into the buffer + // TODO: Instead of G1, we can just add the move directly to the planner... + // { + // destination = current_position; destination = abl.probePos; + // REMEMBER(fr, feedrate_mm_s, XY_PROBE_FEEDRATE_MM_S); + // prepare_line_to_destination(); + // } + sprintf_P(tmp_1, PSTR("G1X%d.%d Y%d.%d F%d"), + int(abl.probePos.x), int(abl.probePos.x * 10) % 10, + int(abl.probePos.y), int(abl.probePos.y * 10) % 10, + XY_PROBE_FEEDRATE + ); + gcode.process_subcommands_now(tmp_1); + + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("destX: ", abl.probePos.x, " Y:", abl.probePos.y); + + // Reset the inner counter back to the start + PR_INNER_VAR = inStart; + + // Get the coordinate of the start of the row/column + abl.probePos = abl.probe_position_lf + abl.gridSpacing * abl.meshCount.asFloat(); + } + + // Wait around until the real axis position reaches the comparison point + // TODO: Use NEAR() because float is imprecise + constexpr AxisEnum axis = TERN(PROBE_Y_FIRST, Y_AXIS, X_AXIS); + const float cmp = abl.probePos[axis] - probe.offset_xy[axis]; + float pos; + for (;;) { + pos = planner.get_axis_position_mm(axis); + if (inInc > 0 ? (pos >= cmp) : (pos <= cmp)) break; + marlin.idle_no_sleep(); + } + //if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM_P(axis == Y_AXIS ? PSTR("Y=") : PSTR("X=", pos); + + safe_delay(4); + abl.measured_z = current_position.z - bdl.read(); + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("x_cur ", planner.get_axis_position_mm(X_AXIS), " z ", abl.measured_z); + + #else // !BD_SENSOR_PROBE_NO_STOP + + abl.measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); + + #endif if (isnan(abl.measured_z)) { set_bed_leveling_enabled(abl.reenable); @@ -732,10 +794,16 @@ G29_TYPE GcodeSuite::G29() { abl.z_values[abl.meshCount.x][abl.meshCount.y] = z; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(abl.meshCount, z)); + #if ENABLED(SOVOL_SV06_RTS) + if (pt_index <= GRID_MAX_POINTS) rts.sendData(pt_index, AUTO_BED_LEVEL_ICON_VP); + rts.sendData(z * 100.0f, AUTO_BED_LEVEL_1POINT_VP + (pt_index - 1) * 2); + rts.gotoPage(ID_ABL_Wait_L, ID_ABL_Wait_D); + #endif + #endif abl.reenable = false; // Don't re-enable after modifying the mesh - idle_no_sleep(); + marlin.idle_no_sleep(); } // inner } // outer @@ -744,7 +812,7 @@ G29_TYPE GcodeSuite::G29() { // Probe at 3 arbitrary points - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing point ", i + 1, "/3."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); @@ -769,7 +837,7 @@ G29_TYPE GcodeSuite::G29() { #endif // AUTO_BED_LEVELING_3POINT - TERN_(HAS_STATUS_MESSAGE, ui.reset_status()); + ui.reset_status(); // Stow the probe. No raise for FIX_MOUNTED_PROBE. if (probe.stow()) { @@ -779,15 +847,15 @@ G29_TYPE GcodeSuite::G29() { } #endif // !PROBE_MANUALLY - // - // G29 Finishing Code - // - // Unless this is a dry run, auto bed leveling will - // definitely be enabled after this point. - // - // If code above wants to continue leveling, it should - // return or loop before this point. - // + /** + * G29 Finishing Code + * + * Unless this is a dry run, auto bed leveling will + * definitely be enabled after this point. + * + * If code above wants to continue leveling, it should + * return or loop before this point. + */ if (DEBUGGING(LEVELING)) DEBUG_POS("> probing complete", current_position); @@ -816,12 +884,12 @@ G29_TYPE GcodeSuite::G29() { // For LINEAR leveling calculate matrix, print reports, correct the position /** - * solve the plane equation ax + by + d = z + * Solve the plane equation ax + by + d = z * A is the matrix with rows [x y 1] for all the probed points * B is the vector of the Z positions - * the normal vector to the plane is formed by the coefficients of the + * The normal vector to the plane is formed by the coefficients of the * plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0 - * so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z + * so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z). */ struct { float a, b, d; } plane_equation_coefficients; @@ -833,11 +901,11 @@ G29_TYPE GcodeSuite::G29() { abl.mean /= abl.abl_points; if (abl.verbose_level) { - SERIAL_ECHOPAIR_F("Eqn coefficients: a: ", plane_equation_coefficients.a, 8); - SERIAL_ECHOPAIR_F(" b: ", plane_equation_coefficients.b, 8); - SERIAL_ECHOPAIR_F(" d: ", plane_equation_coefficients.d, 8); + SERIAL_ECHOPGM("Eqn coefficients: a: ", p_float_t(plane_equation_coefficients.a, 8), + " b: ", p_float_t(plane_equation_coefficients.b, 8), + " d: ", p_float_t(plane_equation_coefficients.d, 8)); if (abl.verbose_level > 2) - SERIAL_ECHOPAIR_F("\nMean of sampled points: ", abl.mean, 8); + SERIAL_ECHOPGM("\nMean of sampled points: ", p_float_t(abl.mean, 8)); SERIAL_EOL(); } @@ -853,9 +921,9 @@ G29_TYPE GcodeSuite::G29() { float min_diff = 999; auto print_topo_map = [&](FSTR_P const title, const bool get_min) { - SERIAL_ECHOF(title); + SERIAL_ECHO(title); for (int8_t yy = abl.grid_points.y - 1; yy >= 0; yy--) { - LOOP_L_N(xx, abl.grid_points.x) { + for (uint8_t xx = 0; xx < abl.grid_points.x; ++xx) { const int ind = abl.indexIntoAB[xx][yy]; xyz_float_t tmp = { abl.eqnAMatrix[ind + 0 * abl.abl_points], abl.eqnAMatrix[ind + 1 * abl.abl_points], 0 }; @@ -864,7 +932,7 @@ G29_TYPE GcodeSuite::G29() { const float subval = get_min ? abl.mean : tmp.z + min_diff, diff = abl.eqnBVector[ind] - subval; SERIAL_CHAR(' '); if (diff >= 0.0) SERIAL_CHAR('+'); // Include + for column alignment - SERIAL_ECHO_F(diff, 5); + SERIAL_ECHO(p_float_t(diff, 5)); } // xx SERIAL_EOL(); } // yy @@ -943,13 +1011,15 @@ G29_TYPE GcodeSuite::G29() { TERN_(HAS_BED_PROBE, probe.move_z_after_probing()); - #ifdef Z_PROBE_END_SCRIPT - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Probe End Script: ", Z_PROBE_END_SCRIPT); + #ifdef EVENT_GCODE_AFTER_G29 + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("After G29 G-code: ", EVENT_GCODE_AFTER_G29); planner.synchronize(); - process_subcommands_now(F(Z_PROBE_END_SCRIPT)); + process_subcommands_now(F(EVENT_GCODE_AFTER_G29)); #endif - TERN_(HAS_MULTI_HOTEND, if (abl.tool_index != 0) tool_change(abl.tool_index)); + TERN_(SOVOL_SV06_RTS, RTS_AutoBedLevelPage()); + + probe.use_probing_tool(false); report_current_position(); diff --git a/Marlin/src/gcode/bedlevel/abl/M421.cpp b/Marlin/src/gcode/bedlevel/abl/M421.cpp index 3272ea1bd2..f66d023190 100644 --- a/Marlin/src/gcode/bedlevel/abl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/abl/M421.cpp @@ -56,8 +56,8 @@ void GcodeSuite::M421() { const float zval = parser.value_linear_units(); uint8_t sx = ix >= 0 ? ix : 0, ex = ix >= 0 ? ix : GRID_MAX_POINTS_X - 1, sy = iy >= 0 ? iy : 0, ey = iy >= 0 ? iy : GRID_MAX_POINTS_Y - 1; - LOOP_S_LE_N(x, sx, ex) { - LOOP_S_LE_N(y, sy, ey) { + for (uint8_t x = sx; x <= ex; ++x) { + for (uint8_t y = sy; y <= ey; ++y) { bedlevel.z_values[x][y] = zval + (hasQ ? bedlevel.z_values[x][y] : 0); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y])); } diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index e98f3d5ee3..a08ecc327d 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -40,13 +40,15 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_LCD_PROUI) - #include "../../../lcd/e3v2/proui/dwin.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../../core/debug_out.h" +#if ENABLED(FT_MOTION) + #include "../../../module/ft_motion.h" +#endif + // Save 130 bytes with non-duplication of PSTR inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" not entered."); } @@ -64,6 +66,10 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" * S5 Reset and disable mesh */ void GcodeSuite::G29() { + + // Potentially disable Fixed-Time Motion for probing + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); + DEBUG_SECTION(log_G29, "G29", true); // G29 Q is also available if debugging @@ -92,7 +98,7 @@ void GcodeSuite::G29() { case MeshReport: SERIAL_ECHOPGM("Mesh Bed Leveling "); if (leveling_is_valid()) { - serialprintln_onoff(planner.leveling_active); + SERIAL_ECHOLN(ON_OFF(planner.leveling_active)); bedlevel.report_mesh(); } else @@ -103,14 +109,11 @@ void GcodeSuite::G29() { bedlevel.reset(); mbl_probe_index = 0; if (!ui.wait_for_move) { - queue.inject(parser.seen_test('N') ? F("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : F("G29S2")); - TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); - TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart()); + if (parser.seen_test('N')) + queue.inject(F("G28" TERN_(CAN_SET_LEVELING_AFTER_G28, "L0"))); // Position bed horizontally and Z probe vertically. - #if defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \ - || defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \ - || defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W) + #if HAS_SAFE_BED_LEVELING xyze_pos_t safe_position = current_position; #ifdef SAFE_BED_LEVELING_START_X safe_position.x = SAFE_BED_LEVELING_START_X; @@ -141,7 +144,11 @@ void GcodeSuite::G29() { #endif do_blocking_move_to(safe_position); - #endif + #endif // HAS_SAFE_BED_LEVELING + + queue.inject(F("G29S2")); + + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); return; } @@ -167,11 +174,10 @@ void GcodeSuite::G29() { // Save Z for the previous mesh position 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); } // If there's another point to sample, move there with optional lift. - if (mbl_probe_index < (GRID_MAX_POINTS)) { + if (mbl_probe_index < GRID_MAX_POINTS) { // Disable software endstops to allow manual adjustment // If G29 is left hanging without completion they won't be re-enabled! SET_SOFT_ENDSTOP_LOOSE(true); @@ -219,7 +225,7 @@ void GcodeSuite::G29() { } } else - return echo_not_entered('J'); + return echo_not_entered('I'); if (parser.seenval('J')) { iy = parser.value_int(); @@ -234,7 +240,6 @@ void GcodeSuite::G29() { if (parser.seenval('Z')) { 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'); diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index ff74f4c6f7..99ba3ce19b 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -33,8 +33,6 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_LCD_PROUI) - #include "../../../lcd/e3v2/proui/dwin.h" #endif /** @@ -66,10 +64,9 @@ void GcodeSuite::M421() { else if (!WITHIN(ij.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(ij.y, 0, GRID_MAX_POINTS_Y - 1)) SERIAL_ERROR_MSG(STR_ERR_MESH_XY); else { - float &zval = bedlevel.z_values[ij.x][ij.y]; // Altering this Mesh Point + float &zval = bedlevel.z_values[ij.x][ij.y]; // Altering this Mesh Point zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh - TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ij.x, ij.y, zval)); } } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index a6dff2d75a..4a0ecffc4b 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -28,6 +28,10 @@ #include "../../module/planner.h" #include "../../module/stepper.h" // for various +#if HAS_HOMING_CURRENT + #include "../../module/motion.h" // for set/restore_homing_current +#endif + #if HAS_MULTI_HOTEND #include "../../module/tool_change.h" #endif @@ -36,28 +40,30 @@ #include "../../feature/bedlevel/bedlevel.h" #endif -#if ENABLED(BD_SENSOR) - #include "../../feature/bedlevel/bdl/bdl.h" -#endif - #if ENABLED(SENSORLESS_HOMING) #include "../../feature/tmc_util.h" #endif -#include "../../module/probe.h" +#if HAS_BED_PROBE + #include "../../module/probe.h" +#endif #if ENABLED(BLTOUCH) #include "../../feature/bltouch.h" #endif +#if ENABLED(FT_MOTION) + #include "../../module/ft_motion.h" +#endif + #include "../../lcd/marlinui.h" #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD) - #include "../../lcd/e3v2/creality/dwin.h" -#elif ENABLED(DWIN_LCD_PROUI) - #include "../../lcd/e3v2/proui/dwin.h" + #include "../../lcd/dwin/creality/dwin.h" +#elif ENABLED(SOVOL_SV06_RTS) + #include "../../lcd/sovol_rts/sovol_rts.h" #endif #if ENABLED(LASER_FEATURE) @@ -81,12 +87,18 @@ const float minfr = _MIN(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)), fr_mm_s = HYPOT(minfr, minfr); + // Set homing current to X and Y axis if defined + TERN_(X_HAS_HOME_CURRENT, set_homing_current(X_AXIS)); + #if Y_HAS_HOME_CURRENT && NONE(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) + set_homing_current(Y_AXIS); + #endif + #if ENABLED(SENSORLESS_HOMING) sensorless_t stealth_states { NUM_AXIS_LIST( TERN0(X_SENSORLESS, tmc_enable_stallguard(stepperX)), TERN0(Y_SENSORLESS, tmc_enable_stallguard(stepperY)), - false, false, false, false + false, false, false, false, false, false, false ) , TERN0(X2_SENSORLESS, tmc_enable_stallguard(stepperX2)) , TERN0(Y2_SENSORLESS, tmc_enable_stallguard(stepperY2)) @@ -99,6 +111,11 @@ current_position.set(0.0, 0.0); + TERN_(X_HAS_HOME_CURRENT, restore_homing_current(X_AXIS)); + #if Y_HAS_HOME_CURRENT && NONE(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) + restore_homing_current(Y_AXIS); + #endif + #if ENABLED(SENSORLESS_HOMING) && DISABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) TERN_(X_SENSORLESS, tmc_disable_stallguard(stepperX, stealth_states.x)); TERN_(X2_SENSORLESS, tmc_disable_stallguard(stepperX2, stealth_states.x2)); @@ -117,6 +134,9 @@ // Disallow Z homing if X or Y homing is needed if (homing_needed_error(_BV(X_AXIS) | _BV(Y_AXIS))) return; + // Potentially disable Fixed-Time Motion for homing + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); + sync_plan_position(); /** @@ -124,14 +144,7 @@ * (Z is already at the right height) */ constexpr xy_float_t safe_homing_xy = { Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT }; - #if HAS_HOME_OFFSET - xy_float_t okay_homing_xy = safe_homing_xy; - okay_homing_xy -= home_offset; - #else - constexpr xy_float_t okay_homing_xy = safe_homing_xy; - #endif - - destination.set(okay_homing_xy, current_position.z); + destination.set(safe_homing_xy, current_position.z); TERN_(HOMING_Z_WITH_PROBE, destination -= probe.offset_xy); @@ -166,7 +179,7 @@ planner.settings.max_acceleration_mm_per_s2[X_AXIS] = 100; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = 100; TERN_(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = 100); - #if HAS_CLASSIC_JERK + #if ENABLED(CLASSIC_JERK) motion_state.jerk_state = planner.max_jerk; planner.max_jerk.set(0, 0 OPTARG(DELTA, 0)); #endif @@ -178,25 +191,31 @@ planner.settings.max_acceleration_mm_per_s2[X_AXIS] = motion_state.acceleration.x; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = motion_state.acceleration.y; TERN_(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = motion_state.acceleration.z); - TERN_(HAS_CLASSIC_JERK, planner.max_jerk = motion_state.jerk_state); + TERN_(CLASSIC_JERK, planner.max_jerk = motion_state.jerk_state); planner.refresh_acceleration_rates(); } #endif // IMPROVE_HOMING_RELIABILITY /** - * G28: Home all axes according to settings + * G28: Auto Home * - * Parameters + * Home all axes according to settings * - * None Home to all axes with no parameters. + * Parameters: + * None Home all axes * With QUICK_HOME enabled XY will home together, then Z. * * L Force leveling state ON (if possible) or OFF after homing (Requires RESTORE_LEVELING_AFTER_G28 or ENABLE_LEVELING_AFTER_G28) * O Home only if the position is not known and trusted * R Raise by n mm/inches before homing + * H Hold the current X/Y position when executing a home Z, or if + * multiple axes are homed, the position when Z home is executed. + * When using a probe for Z Home, positions close to the edge may + * fail with position unreachable due to probe/nozzle offset. This + * can be used to avoid a model. * - * Cartesian/SCARA parameters + * Cartesian/SCARA parameters: * * X Home to the X endstop * Y Home to the Y endstop @@ -206,20 +225,6 @@ void GcodeSuite::G28() { DEBUG_SECTION(log_G28, "G28", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); - TERN_(BD_SENSOR, bdl.config_state = 0); - - /** - * 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; - DualXMode IDEX_saved_mode = dual_x_carriage_mode; - #endif - #if ENABLED(MARLIN_DEV_MODE) if (parser.seen_test('S')) { LOOP_NUM_AXES(a) set_axis_is_at_home((AxisEnum)a); @@ -230,6 +235,13 @@ void GcodeSuite::G28() { } #endif + /** + * 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 + // Home (O)nly if position is unknown if (!axes_should_home() && parser.seen_test('O')) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> homing not needed, skip"); @@ -241,193 +253,268 @@ void GcodeSuite::G28() { set_and_report_grblstate(M_HOMING); #endif - TERN_(HAS_DWIN_E3V2_BASIC, DWIN_HomingStart()); + TERN_(DWIN_CREALITY_LCD, dwinHomingStart()); TERN_(EXTENSIBLE_UI, ExtUI::onHomingStart()); planner.synchronize(); // Wait for planner moves to finish! - SET_SOFT_ENDSTOP_LOOSE(false); // Reset a leftover 'loose' motion state - - // Disable the leveling matrix before homing - #if CAN_SET_LEVELING_AFTER_G28 - const bool leveling_restore_state = parser.boolval('L', TERN1(RESTORE_LEVELING_AFTER_G28, planner.leveling_active)); - #endif - - // Cancel any prior G29 session - TERN_(PROBE_MANUALLY, g29_in_progress = false); - - // Disable leveling before homing - TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); - - // Reset to the XY plane - TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); - // Count this command as movement / activity reset_stepper_timeout(); - #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT) - #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || (ENABLED(DELTA) && 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) - #define HAS_HOMING_CURRENT 1 - #endif + #if NUM_AXES - #if HAS_HOMING_CURRENT - auto debug_current = [](FSTR_P const s, const int16_t a, const int16_t b) { - DEBUG_ECHOF(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b); - }; - #if HAS_CURRENT_HOME(X) - const int16_t tmc_save_current_X = stepperX.getMilliamps(); - stepperX.rms_current(X_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_X), tmc_save_current_X, X_CURRENT_HOME); + #if ENABLED(DUAL_X_CARRIAGE) + bool IDEX_saved_duplication_state = extruder_duplication_enabled; + DualXMode IDEX_saved_mode = dual_x_carriage_mode; #endif - #if HAS_CURRENT_HOME(X2) - const int16_t tmc_save_current_X2 = stepperX2.getMilliamps(); - stepperX2.rms_current(X2_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_X2), tmc_save_current_X2, X2_CURRENT_HOME); + + SET_SOFT_ENDSTOP_LOOSE(false); // Reset a leftover 'loose' motion state + + // Disable the leveling matrix before homing + #if CAN_SET_LEVELING_AFTER_G28 + const bool leveling_restore_state = parser.boolval('L', TERN1(RESTORE_LEVELING_AFTER_G28, planner.leveling_active)); #endif - #if HAS_CURRENT_HOME(Y) - const int16_t tmc_save_current_Y = stepperY.getMilliamps(); - stepperY.rms_current(Y_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_Y), tmc_save_current_Y, Y_CURRENT_HOME); + + // Cancel any prior G29 session + TERN_(PROBE_MANUALLY, g29_in_progress = false); + + // Disable leveling before homing + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); + + // Reset to the XY plane + TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); + + #if ENABLED(IMPROVE_HOMING_RELIABILITY) + motion_state_t saved_motion_state = begin_slow_homing(); #endif - #if HAS_CURRENT_HOME(Y2) - const int16_t tmc_save_current_Y2 = stepperY2.getMilliamps(); - stepperY2.rms_current(Y2_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_Y2), tmc_save_current_Y2, Y2_CURRENT_HOME); + + // Potentially disable Fixed-Time Motion for homing + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); + + // Always home with tool 0 active + #if HAS_MULTI_HOTEND + #if DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE) + const uint8_t old_tool_index = active_extruder; + #endif + // PARKING_EXTRUDER homing requires different handling of movement / solenoid activation, depending on the side of homing + #if ENABLED(PARKING_EXTRUDER) + const bool homed_towards_tool = old_tool_index == TERN(X_HOME_TO_MIN, 0, 1), + pe_final_change_must_unpark = parking_extruder_unpark_after_homing(old_tool_index, homed_towards_tool); + #endif + tool_change(0, true); #endif - #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) - const int16_t tmc_save_current_Z = stepperZ.getMilliamps(); - stepperZ.rms_current(Z_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_Z), tmc_save_current_Z, Z_CURRENT_HOME); - #endif - #if HAS_CURRENT_HOME(I) - const int16_t tmc_save_current_I = stepperI.getMilliamps(); - stepperI.rms_current(I_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_I), tmc_save_current_I, I_CURRENT_HOME); - #endif - #if HAS_CURRENT_HOME(J) - const int16_t tmc_save_current_J = stepperJ.getMilliamps(); - stepperJ.rms_current(J_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_J), tmc_save_current_J, J_CURRENT_HOME); - #endif - #if HAS_CURRENT_HOME(K) - const int16_t tmc_save_current_K = stepperK.getMilliamps(); - stepperK.rms_current(K_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_K), tmc_save_current_K, K_CURRENT_HOME); - #endif - #if HAS_CURRENT_HOME(U) - const int16_t tmc_save_current_U = stepperU.getMilliamps(); - stepperU.rms_current(U_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_U), tmc_save_current_U, U_CURRENT_HOME); - #endif - #if HAS_CURRENT_HOME(V) - const int16_t tmc_save_current_V = stepperV.getMilliamps(); - stepperV.rms_current(V_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(STR_V), tmc_save_current_V, V_CURRENT_HOME); - #endif - #if HAS_CURRENT_HOME(W) - const int16_t tmc_save_current_W = stepperW.getMilliamps(); - 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) - motion_state_t saved_motion_state = begin_slow_homing(); - #endif + TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); - // Always home with tool 0 active - #if HAS_MULTI_HOTEND - #if DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE) - const uint8_t old_tool_index = active_extruder; - #endif - // PARKING_EXTRUDER homing requires different handling of movement / solenoid activation, depending on the side of homing - #if ENABLED(PARKING_EXTRUDER) - const bool pe_final_change_must_unpark = parking_extruder_unpark_after_homing(old_tool_index, X_HOME_DIR + 1 == old_tool_index * 2); - #endif - tool_change(0, true); - #endif + remember_feedrate_scaling_off(); - TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); - - remember_feedrate_scaling_off(); - - endstops.enable(true); // Enable endstops for next homing move - - #if ENABLED(DELTA) - - constexpr bool doZ = true; // for NANODLP_Z_SYNC if your DLP is on a DELTA - - home_delta(); - - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); - - #elif ENABLED(AXEL_TPARA) - - constexpr bool doZ = true; // for NANODLP_Z_SYNC if your DLP is on a TPARA - - home_TPARA(); - - #else - - #define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS)))) - - const bool homeZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')), - NUM_AXIS_LIST( // Other axes should be homed before Z safe-homing - needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED - needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K), - needU = _UNSAFE(U), needV = _UNSAFE(V), needW = _UNSAFE(W) - ), - NUM_AXIS_LIST( // Home each axis if needed or flagged - homeX = needX || parser.seen_test('X'), - homeY = needY || parser.seen_test('Y'), - homeZZ = homeZ, - homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), - homeK = needK || parser.seen_test(AXIS6_NAME), homeU = needU || parser.seen_test(AXIS7_NAME), - homeV = needV || parser.seen_test(AXIS8_NAME), homeW = needW || parser.seen_test(AXIS9_NAME) - ), - home_all = NUM_AXIS_GANG( // Home-all if all or none are flagged - homeX == homeX, && homeY == homeX, && homeZ == homeX, - && homeI == homeX, && homeJ == homeX, && homeK == homeX, - && homeU == homeX, && homeV == homeX, && homeW == homeX - ), - NUM_AXIS_LIST( - doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ, - doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK, - doU = home_all || homeU, doV = home_all || homeV, doW = home_all || homeW - ); + endstops.enable(true); // Enable endstops for next homing move #if HAS_Z_AXIS - UNUSED(needZ); UNUSED(homeZZ); - #else - constexpr bool doZ = false; + bool finalRaiseZ = false; #endif - TERN_(HOME_Z_FIRST, if (doZ) homeaxis(Z_AXIS)); + #if ENABLED(DELTA) - const bool seenR = parser.seenval('R'); - const float z_homing_height = seenR ? parser.value_linear_units() : Z_HOMING_HEIGHT; + constexpr bool doZ = true; // for NANODLP_Z_SYNC if your DLP is on a DELTA - if (z_homing_height && (seenR || NUM_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK, || doU, || doV, || doW))) { - // Raise Z before homing any other axes and z is not already high enough (never lower z) - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Raise Z (before homing) by ", z_homing_height); - do_z_clearance(z_homing_height); - TERN_(BLTOUCH, bltouch.init()); - } + home_delta(); - // Diagonal move first if both are homing - TERN_(QUICK_HOME, if (doX && doY) quick_home_xy()); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); - // Home Y (before X) - if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX))) - homeaxis(Y_AXIS); + #elif ENABLED(AXEL_TPARA) - // Home X - if (doX || (doY && ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X))) { + constexpr bool doZ = true; // for NANODLP_Z_SYNC if your DLP is on a TPARA - #if ENABLED(DUAL_X_CARRIAGE) + home_TPARA(); + + #else // !DELTA && !AXEL_TPARA + + #define _UNSAFE(A) TERN0(Z_SAFE_HOMING, homeZZ && axis_should_home(_AXIS(A))) + + const bool homeZZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')), + NUM_AXIS_LIST_( // Other axes should be homed before Z safe-homing + needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED + needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K), + needU = _UNSAFE(U), needV = _UNSAFE(V), needW = _UNSAFE(W) + ) + NUM_AXIS_LIST_( // Home each axis if needed or flagged + homeX = needX || parser.seen_test('X'), + homeY = needY || parser.seen_test('Y'), + homeZ = homeZZ, + homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), + homeK = needK || parser.seen_test(AXIS6_NAME), homeU = needU || parser.seen_test(AXIS7_NAME), + homeV = needV || parser.seen_test(AXIS8_NAME), homeW = needW || parser.seen_test(AXIS9_NAME) + ) + home_all = NUM_AXIS_GANG_( // Home-all if all or none are flagged + homeX == homeX, && homeY == homeX, && homeZ == homeX, + && homeI == homeX, && homeJ == homeX, && homeK == homeX, + && homeU == homeX, && homeV == homeX, && homeW == homeX + ) + NUM_AXIS_LIST( + doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ, + doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK, + doU = home_all || homeU, doV = home_all || homeV, doW = home_all || homeW + ); + + #if !HAS_Y_AXIS + constexpr bool doY = false; + #endif + + #if HAS_Z_AXIS + + UNUSED(needZ); + + // Z may home first, e.g., when homing away from the bed. + // This is also permitted when homing with a Z endstop. + if (TERN0(HOME_Z_FIRST, doZ)) homeaxis(Z_AXIS); + + // 'R' to specify a specific raise. 'R0' indicates no raise, e.g., for recovery.resume + // When 'R0' is used, there should already be adequate clearance, e.g., from homing Z to max. + const bool seenR = parser.seenval('R'); + + // Use raise given by 'R' or Z_CLEARANCE_FOR_HOMING (above the probe trigger point) + float z_homing_height = seenR ? parser.value_linear_units() : Z_CLEARANCE_FOR_HOMING; + + // Check for any lateral motion that might require clearance + const bool may_skate = seenR NUM_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK, || doU, || doV, || doW); + + if (seenR && z_homing_height == 0) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("R0 = No Z raise"); + } + else { + bool with_probe = ENABLED(HOMING_Z_WITH_PROBE); + // Raise above the current Z (which should be synced in the planner) + // The "height" for Z is a coordinate. But if Z is not trusted/homed make it relative. + if (seenR || !(z_min_trusted || axis_should_home(Z_AXIS))) { + z_homing_height += current_position.z; + with_probe = false; + } + + if (may_skate) { + // Apply Z clearance before doing any lateral motion + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Raise Z before homing:"); + do_z_clearance(z_homing_height, with_probe); + } + } + + // Init BLTouch ahead of any lateral motion, even if not homing with the probe + TERN_(BLTOUCH, if (may_skate) bltouch.init()); + + #endif // HAS_Z_AXIS + + // Diagonal move first if both are homing + TERN_(QUICK_HOME, if (doX && doY) quick_home_xy()); + + #if HAS_Y_AXIS + // Home Y (before X) + if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX))) + homeaxis(Y_AXIS); + #endif + + // Home X + #if HAS_X_AXIS + if (doX || (doY && ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X))) { + + #if ENABLED(DUAL_X_CARRIAGE) + + // Always home the 2nd (right) extruder first + active_extruder = 1; + homeaxis(X_AXIS); + + // Remember this extruder's position for later tool change + inactive_extruder_x = current_position.x; + + // Home the 1st (left) extruder + active_extruder = 0; + homeaxis(X_AXIS); + + // Consider the active extruder to be in its "parked" position + idex_set_parked(); + + #else + + homeaxis(X_AXIS); + + #endif + } + #endif // HAS_X_AXIS + + #if ALL(FOAMCUTTER_XYUV, HAS_I_AXIS) + // Home I (after X) + if (doI) homeaxis(I_AXIS); + #endif + + #if HAS_Y_AXIS + // Home Y (after X) + if (DISABLED(HOME_Y_BEFORE_X) && doY) homeaxis(Y_AXIS); + #endif + + #if ALL(FOAMCUTTER_XYUV, HAS_J_AXIS) + // Home J (after Y) + if (doJ) homeaxis(J_AXIS); + #endif + + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); + + #if ENABLED(FOAMCUTTER_XYUV) + + // Skip homing of unused Z axis for foamcutters + if (doZ) set_axis_is_at_home(Z_AXIS); + + #elif HAS_Z_AXIS + + // Home Z last if homing towards the bed + #if DISABLED(HOME_Z_FIRST) + if (doZ) { + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + stepper.set_all_z_lock(false); + stepper.set_separate_multi_axis(false); + #endif + + #if ENABLED(Z_SAFE_HOMING) + // H means hold the current X/Y position when probing. + // Otherwise move to the define safe X/Y position before homing Z. + if (!parser.seen_test('H')) + home_z_safely(); + else + homeaxis(Z_AXIS); + #else + homeaxis(Z_AXIS); + #endif + + #if ANY(Z_HOME_TO_MIN, ALLOW_Z_AFTER_HOMING) + finalRaiseZ = true; + #endif + } + #endif + + SECONDARY_AXIS_CODE( + if (doI) homeaxis(I_AXIS), + if (doJ) homeaxis(J_AXIS), + if (doK) homeaxis(K_AXIS), + if (doU) homeaxis(U_AXIS), + if (doV) homeaxis(V_AXIS), + if (doW) homeaxis(W_AXIS) + ); + + #endif // HAS_Z_AXIS + + sync_plan_position(); + + #endif + + /** + * Preserve DXC mode across a G28 for IDEX printers in DXC_DUPLICATION_MODE. + * This is important because it lets a user use the LCD Panel to set an IDEX Duplication mode, and + * then print a standard G-Code file that contains a single print that does a G28 and has no other + * IDEX specific commands in it. + */ + #if ENABLED(DUAL_X_CARRIAGE) + + if (idex_is_duplicating()) { + + TERN_(IMPROVE_HOMING_RELIABILITY, saved_motion_state = begin_slow_homing()); // Always home the 2nd (right) extruder first active_extruder = 1; @@ -440,168 +527,63 @@ void GcodeSuite::G28() { active_extruder = 0; homeaxis(X_AXIS); - // Consider the active extruder to be in its "parked" position + // Consider the active extruder to be parked idex_set_parked(); - #else + dual_x_carriage_mode = IDEX_saved_mode; + set_duplication_enabled(IDEX_saved_duplication_state); - homeaxis(X_AXIS); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); + } - #endif - } + #endif // DUAL_X_CARRIAGE - #if BOTH(FOAMCUTTER_XYUV, HAS_I_AXIS) - // Home I (after X) - if (doI) homeaxis(I_AXIS); + endstops.not_homing(); + + // Clear endstop state for polled stallGuard endstops + TERN_(SPI_ENDSTOPS, endstops.clear_endstop_state()); + + // Move to a height where we can use the full xy-area + TERN_(DELTA_HOME_TO_SAFE_ZONE, do_blocking_move_to_z(delta_clip_start_height)); + + #if HAS_Z_AXIS + // Move to the configured Z only if Z was homed to MIN, because machines that + // home to MAX historically expect 'G28 Z' to be safe to use at the end of a + // print, and do_move_after_z_homing is not very nuanced. + if (finalRaiseZ) do_move_after_z_homing(); #endif - // Home Y (after X) - if (DISABLED(HOME_Y_BEFORE_X) && doY) - homeaxis(Y_AXIS); + TERN_(CAN_SET_LEVELING_AFTER_G28, if (leveling_restore_state) set_bed_leveling_enabled()); - #if BOTH(FOAMCUTTER_XYUV, HAS_J_AXIS) - // Home J (after Y) - if (doJ) homeaxis(J_AXIS); + // Restore the active tool after homing + #if HAS_MULTI_HOTEND && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE)) + tool_change(old_tool_index, TERN(PARKING_EXTRUDER, !pe_final_change_must_unpark, DISABLED(DUAL_X_CARRIAGE))); // Do move if one of these #endif - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); - - #if ENABLED(FOAMCUTTER_XYUV) - // skip homing of unused Z axis for foamcutters - if (doZ) set_axis_is_at_home(Z_AXIS); - #else - // Home Z last if homing towards the bed - #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST) - if (doZ) { - #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) - stepper.set_all_z_lock(false); - stepper.set_separate_multi_axis(false); - #endif - - #if ENABLED(Z_SAFE_HOMING) - if (TERN1(POWER_LOSS_RECOVERY, !parser.seen_test('H'))) home_z_safely(); else homeaxis(Z_AXIS); - #else - homeaxis(Z_AXIS); - #endif - probe.move_z_after_homing(); - } - #endif - - SECONDARY_AXIS_CODE( - if (doI) homeaxis(I_AXIS), - if (doJ) homeaxis(J_AXIS), - if (doK) homeaxis(K_AXIS), - if (doU) homeaxis(U_AXIS), - if (doV) homeaxis(V_AXIS), - if (doW) homeaxis(W_AXIS) - ); + #ifdef XY_AFTER_HOMING + if (!axes_should_home(_BV(X_AXIS) | _BV(Y_AXIS))) + do_blocking_move_to(xy_pos_t(XY_AFTER_HOMING)); #endif - sync_plan_position(); + restore_feedrate_and_scaling(); - #endif + if (ENABLED(NANODLP_Z_SYNC) && (ENABLED(NANODLP_ALL_AXIS) || TERN0(HAS_Z_AXIS, doZ))) + SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); - /** - * Preserve DXC mode across a G28 for IDEX printers in DXC_DUPLICATION_MODE. - * This is important because it lets a user use the LCD Panel to set an IDEX Duplication mode, and - * then print a standard GCode file that contains a single print that does a G28 and has no other - * IDEX specific commands in it. - */ - #if ENABLED(DUAL_X_CARRIAGE) - - if (idex_is_duplicating()) { - - TERN_(IMPROVE_HOMING_RELIABILITY, saved_motion_state = begin_slow_homing()); - - // Always home the 2nd (right) extruder first - active_extruder = 1; - homeaxis(X_AXIS); - - // Remember this extruder's position for later tool change - inactive_extruder_x = current_position.x; - - // Home the 1st (left) extruder - active_extruder = 0; - homeaxis(X_AXIS); - - // Consider the active extruder to be parked - idex_set_parked(); - - dual_x_carriage_mode = IDEX_saved_mode; - set_duplication_enabled(IDEX_saved_duplication_state); - - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); - } - - #endif // DUAL_X_CARRIAGE - - endstops.not_homing(); - - // Clear endstop state for polled stallGuard endstops - TERN_(SPI_ENDSTOPS, endstops.clear_endstop_state()); - - // Move to a height where we can use the full xy-area - TERN_(DELTA_HOME_TO_SAFE_ZONE, do_blocking_move_to_z(delta_clip_start_height)); - - TERN_(CAN_SET_LEVELING_AFTER_G28, if (leveling_restore_state) set_bed_leveling_enabled()); - - restore_feedrate_and_scaling(); - - // Restore the active tool after homing - #if HAS_MULTI_HOTEND && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE)) - tool_change(old_tool_index, TERN(PARKING_EXTRUDER, !pe_final_change_must_unpark, DISABLED(DUAL_X_CARRIAGE))); // Do move if one of these - #endif - - #if HAS_HOMING_CURRENT - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Restore driver current..."); - #if HAS_CURRENT_HOME(X) - stepperX.rms_current(tmc_save_current_X); - #endif - #if HAS_CURRENT_HOME(X2) - stepperX2.rms_current(tmc_save_current_X2); - #endif - #if HAS_CURRENT_HOME(Y) - stepperY.rms_current(tmc_save_current_Y); - #endif - #if HAS_CURRENT_HOME(Y2) - stepperY2.rms_current(tmc_save_current_Y2); - #endif - #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) - stepperZ.rms_current(tmc_save_current_Z); - #endif - #if HAS_CURRENT_HOME(I) - stepperI.rms_current(tmc_save_current_I); - #endif - #if HAS_CURRENT_HOME(J) - stepperJ.rms_current(tmc_save_current_J); - #endif - #if HAS_CURRENT_HOME(K) - stepperK.rms_current(tmc_save_current_K); - #endif - #if HAS_CURRENT_HOME(U) - stepperU.rms_current(tmc_save_current_U); - #endif - #if HAS_CURRENT_HOME(V) - stepperV.rms_current(tmc_save_current_V); - #endif - #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 + #endif // NUM_AXES ui.refresh(); - TERN_(HAS_DWIN_E3V2_BASIC, DWIN_HomingDone()); + TERN_(SOVOL_SV06_RTS, RTS_MoveAxisHoming()); + TERN_(DWIN_CREALITY_LCD, dwinHomingDone()); TERN_(EXTENSIBLE_UI, ExtUI::onHomingDone()); report_current_position(); - if (ENABLED(NANODLP_Z_SYNC) && (doZ || ENABLED(NANODLP_ALL_AXIS))) - SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); - TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(old_grblstate)); + #ifdef EVENT_GCODE_AFTER_HOMING + gcode.process_subcommands_now(F(EVENT_GCODE_AFTER_HOMING)); + #endif + } diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 656c23cb78..0a8dd459ca 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -35,18 +35,14 @@ #include "../../module/probe.h" #endif -#if HAS_MULTI_HOTEND - #include "../../module/tool_change.h" -#endif - #if HAS_LEVELING #include "../../feature/bedlevel/bedlevel.h" #endif constexpr uint8_t _7P_STEP = 1, // 7-point step - to change number of calibration points _4P_STEP = _7P_STEP * 2, // 4-point step - NPP = _7P_STEP * 6; // number of calibration points on the radius -enum CalEnum : char { // the 7 main calibration points - add definitions if needed + NPP = _7P_STEP * 6; // Number of calibration points on the radius +enum CalEnum : char { // The 7 main calibration points - add definitions if needed CEN = 0, __A = 1, _AB = __A + _7P_STEP, @@ -63,22 +59,18 @@ enum CalEnum : char { // the 7 main calibration points - #define LOOP_CAL_RAD(VAR) LOOP_CAL_PT(VAR, __A, _7P_STEP) #define LOOP_CAL_ACT(VAR, _4P, _OP) LOOP_CAL_PT(VAR, _OP ? _AB : __A, _4P ? _4P_STEP : _7P_STEP) -#if HAS_MULTI_HOTEND - const uint8_t old_tool_index = active_extruder; -#endif - float lcd_probe_pt(const xy_pos_t &xy); void ac_home() { endstops.enable(true); - TERN_(SENSORLESS_HOMING, endstops.set_homing_current(true)); + TERN_(IMPROVE_HOMING_RELIABILITY, planner.enable_stall_prevention(true)); home_delta(); - TERN_(SENSORLESS_HOMING, endstops.set_homing_current(false)); + TERN_(IMPROVE_HOMING_RELIABILITY, planner.enable_stall_prevention(false)); endstops.not_homing(); } void ac_setup(const bool reset_bed) { - TERN_(HAS_MULTI_HOTEND, tool_change(0, true)); + TERN_(HAS_BED_PROBE, probe.use_probing_tool()); planner.synchronize(); remember_feedrate_scaling_off(); @@ -88,21 +80,20 @@ void ac_setup(const bool reset_bed) { #endif } -void ac_cleanup(TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index)) { +void ac_cleanup() { TERN_(DELTA_HOME_TO_SAFE_ZONE, do_blocking_move_to_z(delta_clip_start_height)); TERN_(HAS_BED_PROBE, probe.stow()); restore_feedrate_and_scaling(); - TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, true)); + TERN_(HAS_BED_PROBE, probe.use_probing_tool(false)); } -void print_signed_float(FSTR_P const prefix, const_float_t f) { - SERIAL_ECHOPGM(" "); - SERIAL_ECHOF(prefix, AS_CHAR(':')); +void print_signed_float(FSTR_P const prefix, const float f) { + SERIAL_ECHO(F(" "), prefix, C(':')); serial_offset(f); } /** - * - Print the delta settings + * - Print the delta settings */ static void print_calibration_settings(const bool end_stops, const bool tower_angles) { SERIAL_ECHOPGM(".Height:", delta_height); @@ -128,7 +119,7 @@ static void print_calibration_settings(const bool end_stops, const bool tower_an } /** - * - Print the probe results + * - Print the probe results */ static void print_calibration_results(const float z_pt[NPP + 1], const bool tower_points, const bool opposite_points) { SERIAL_ECHOPGM(". "); @@ -152,7 +143,7 @@ static void print_calibration_results(const float z_pt[NPP + 1], const bool towe } /** - * - Calculate the standard deviation from the zero plane + * - Calculate the standard deviation from the zero plane */ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool _1p_cal, const bool _4p_cal, const bool _4p_opp) { if (!_0p_cal) { @@ -163,18 +154,18 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool S2 += sq(z_pt[rad]); N++; } - return LROUND(SQRT(S2 / N) * 1000.0f) / 1000.0f + 0.00001f; + return LROUND(SQRT(S2 / N) * 1000.0f) * 0.001f + 0.00001f; } } return 0.00001f; } /** - * - Probe a point + * - Probe a point */ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool probe_at_offset) { #if HAS_BED_PROBE - return probe.probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, probe_at_offset, false); + return probe.probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, probe_at_offset, false, Z_PROBE_LOW_POINT, Z_TWEEN_SAFE_CLEARANCE, true); #else UNUSED(stow); return lcd_probe_pt(xy); @@ -182,7 +173,7 @@ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool p } /** - * - Probe a grid + * - Probe a grid */ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_points, const float dcr, const bool towers_set, const bool stow_after_each, const bool probe_at_offset) { const bool _0p_calibration = probe_points == 0, @@ -206,13 +197,13 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi if (!_0p_calibration) { - if (!_7p_no_intermediates && !_7p_4_intermediates && !_7p_11_intermediates) { // probe the center + if (!_7p_no_intermediates && !_7p_4_intermediates && !_7p_11_intermediates) { // Probe the center const xy_pos_t center{0}; z_pt[CEN] += calibration_probe(center, stow_after_each, probe_at_offset); if (isnan(z_pt[CEN])) return false; } - if (_7p_calibration) { // probe extra center points + if (_7p_calibration) { // Probe extra center points const float start = _7p_9_center ? float(_CA) + _7P_STEP / 3.0f : _7p_6_center ? float(_CA) : float(__C), steps = _7p_9_center ? _4P_STEP / 3.0f : _7p_6_center ? _7P_STEP : _4P_STEP; I_LOOP_CAL_PT(rad, start, steps) { @@ -225,7 +216,7 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi z_pt[CEN] /= float(_7p_2_intermediates ? 7 : probe_points); } - if (!_1p_calibration) { // probe the radius + if (!_1p_calibration) { // Probe the radius const CalEnum start = _4p_opposite_points ? _AB : __A; const float steps = _7p_14_intermediates ? _7P_STEP / 15.0f : // 15r * 6 + 10c = 100 _7p_11_intermediates ? _7P_STEP / 12.0f : // 12r * 6 + 9c = 81 @@ -250,7 +241,7 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi z_pt[uint8_t(LROUND(rad - interpol + NPP - 1)) % NPP + 1] += z_temp * sq(cos(RADIANS(interpol * 90))); z_pt[uint8_t(LROUND(rad - interpol)) % NPP + 1] += z_temp * sq(sin(RADIANS(interpol * 90))); } - zig_zag = !zig_zag; + FLIP(zig_zag); } if (_7p_intermed_points) LOOP_CAL_RAD(rad) @@ -263,10 +254,11 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi } /** - * kinematics routines and auto tune matrix scaling parameters: - * see https://github.com/LVD-AC/Marlin-AC/tree/1.1.x-AC/documentation for - * - formulae for approximative forward kinematics in the end-stop displacement matrix - * - definition of the matrix scaling parameters + * Kinematics routines and auto tune matrix scaling parameters + * + * NOTE: See https://github.com/LVD-AC/Marlin-AC/tree/1.1.x-AC/documentation for: + * - Formula for approximative forward kinematics in the end-stop displacement matrix + * - Definition of the matrix scaling parameters */ static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_at_pt_axis[NPP + 1], const float dcr) { xyz_pos_t pos{0}; @@ -323,7 +315,7 @@ static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], const float d static float auto_tune_h(const float dcr) { const float r_quot = dcr / delta_radius; - return RECIPROCAL(r_quot / (2.0f / 3.0f)); // (2/3)/CR + return RECIPROCAL(r_quot * (3.0f / 2.0f)); // (2/3)/CR } static float auto_tune_r(const float dcr) { @@ -355,43 +347,43 @@ static float auto_tune_a(const float dcr) { } /** - * G33 - Delta '1-4-7-point' Auto-Calibration - * Calibrate height, z_offset, endstops, delta radius, and tower angles. + * G33: Delta Auto Calibration + * + * Calibrate height, z_offset, endstops, delta radius, and tower angles. * * Parameters: + * P Number of probe points: + * P0 Normalizes end-stops and tower angle corrections only (no probing) + * P1 Probe center and set height only + * P2 Probe center and towers. Set height, endstops, and delta radius + * P3 Probe all positions - center, towers and opposite towers. Set all + * P4-P10 Probe all positions with intermediate locations, averaging them * - * Pn Number of probe points: - * P0 Normalizes calibration. - * P1 Calibrates height only with center probe. - * P2 Probe center and towers. Calibrate height, endstops and delta radius. - * P3 Probe all positions: center, towers and opposite towers. Calibrate all. - * P4-P10 Probe all positions at different intermediate locations and average them. + * R Temporarily reduce the size of the probe grid by the specified amount * - * Rn.nn Temporary reduce the probe grid by the specified amount (mm) + * T Disable tower angle corrections calibration (P3-P7) * - * T Don't calibrate tower angle corrections + * C Calibration precision; if omitted iterations stop at best achievable precision * - * Cn.nn Calibration precision; when omitted calibrates to maximum precision + * F<1-30> Run (“forceâ€) this number of iterations and take the best result * - * Fn Force to run at least n iterations and take the best result + * V Verbose level: + * V0 Dry-run mode. Report settings and probe results. No calibration + * V1 Report start and end settings only + * V2 Report settings at each iteration + * V3 Report settings and probe results * - * Vn Verbose level: - * V0 Dry-run mode. Report settings and probe results. No calibration. - * V1 Report start and end settings only - * V2 Report settings at each iteration - * V3 Report settings and probe results + * E Engage the probe for each point * - * E Engage the probe for each point + * O Probe at probe-offset-relative positions instead of the required kinematic points * - * O Probe at offsetted probe positions (this is wrong but it seems to work) - * - * With SENSORLESS_PROBING: - * Use these flags to calibrate stall sensitivity: (e.g., `G33 P1 Y Z` to calibrate X only.) - * 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 + * With HAS_DELTA_SENSORLESS_PROBING: + * Use these flags to calibrate stall sensitivity: + * Example: G33 P1 Y Z - to calibrate X only + * X Don't activate StallGuard on X + * Y Don't activate StallGuard on Y + * Z Don't activate StallGuard on Z + * S Save offset_sensorless_adj */ void GcodeSuite::G33() { @@ -399,7 +391,7 @@ void GcodeSuite::G33() { const int8_t probe_points = parser.intval('P', DELTA_CALIBRATION_DEFAULT_POINTS); if (!WITHIN(probe_points, 0, 10)) { - SERIAL_ECHOLNPGM("?(P)oints implausible (0-10)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(P)oints implausible (0-10).")); return; } @@ -407,30 +399,30 @@ void GcodeSuite::G33() { towers_set = !parser.seen_test('T'); // The calibration radius is set to a calculated value - float dcr = probe_at_offset ? DELTA_PRINTABLE_RADIUS : DELTA_PRINTABLE_RADIUS - PROBING_MARGIN; + float dcr = probe_at_offset ? PRINTABLE_RADIUS : PRINTABLE_RADIUS - PROBING_MARGIN; #if HAS_PROBE_XY_OFFSET const float total_offset = HYPOT(probe.offset_xy.x, probe.offset_xy.y); dcr -= probe_at_offset ? _MAX(total_offset, PROBING_MARGIN) : total_offset; #endif - NOMORE(dcr, DELTA_PRINTABLE_RADIUS); + NOMORE(dcr, PRINTABLE_RADIUS); 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) { - SERIAL_ECHOLNPGM("?(C)alibration precision implausible (>=0)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(C)alibration precision implausible (>=0).")); return; } const int8_t force_iterations = parser.intval('F', 0); if (!WITHIN(force_iterations, 0, 30)) { - SERIAL_ECHOLNPGM("?(F)orce iteration implausible (0-30)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(F)orce iteration implausible (0-30).")); return; } const int8_t verbose_level = parser.byteval('V', 1); if (!WITHIN(verbose_level, 0, 3)) { - SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-3)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(V)erbose level implausible (0-3).")); return; } @@ -464,9 +456,8 @@ void GcodeSuite::G33() { SERIAL_ECHOLNPGM("G33 Auto Calibrate"); // Report settings - PGM_P const checkingac = PSTR("Checking... AC"); - SERIAL_ECHOPGM_P(checkingac); - SERIAL_ECHOPGM(" at radius:", dcr); + FSTR_P const checkingac = F("Checking... AC"); + SERIAL_ECHO(checkingac, F(" at radius:"), dcr); if (verbose_level == 0) SERIAL_ECHOPGM(" (DRY-RUN)"); SERIAL_EOL(); ui.set_status(checkingac); @@ -480,8 +471,7 @@ void GcodeSuite::G33() { #if HAS_DELTA_SENSORLESS_PROBING if (verbose_level > 0 && do_save_offset_adj) { offset_sensorless_adj.reset(); - - auto caltower = [&](Probe::sense_bool_t s){ + 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; @@ -492,22 +482,22 @@ void GcodeSuite::G33() { caltower({ false, true, false }); // B caltower({ false, false, true }); // C - probe.test_sensitivity = { true, true, true }; // reset to all + probe.test_sensitivity = { true, true, true }; // Reset to all } #endif - do { // start iterations + do { // Start iterations float z_at_pt[NPP + 1] = { 0.0f }; - test_precision = zero_std_dev_old != 999.0f ? (zero_std_dev + zero_std_dev_old) / 2.0f : zero_std_dev; + test_precision = zero_std_dev_old != 999.0f ? (zero_std_dev + zero_std_dev_old) * 0.5f : zero_std_dev; iterations++; // Probe the points zero_std_dev_old = zero_std_dev; if (!probe_calibration_points(z_at_pt, probe_points, dcr, towers_set, stow_after_each, probe_at_offset)) { SERIAL_ECHOLNPGM("Correct delta settings with M665 and M666"); - return ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index)); + return ac_cleanup(); } zero_std_dev = std_dev_points(z_at_pt, _0p_calibration, _1p_calibration, _4p_calibration, _4p_opposite_points); @@ -516,11 +506,11 @@ void GcodeSuite::G33() { if ((zero_std_dev < test_precision || iterations <= force_iterations) && zero_std_dev > calibration_precision) { #if !HAS_BED_PROBE - test_precision = 0.0f; // forced end + test_precision = 0.0f; // Forced end #endif if (zero_std_dev < zero_std_dev_min) { - // set roll-back point + // Set roll-back point e_old = delta_endstop_adj; r_old = delta_radius; h_old = delta_height; @@ -531,19 +521,20 @@ void GcodeSuite::G33() { float r_delta = 0.0f; /** - * convergence matrices: - * see https://github.com/LVD-AC/Marlin-AC/tree/1.1.x-AC/documentation for - * - definition of the matrix scaling parameters - * - matrices for 4 and 7 point calibration + * Convergence matrices + * + * NOTE: See https://github.com/LVD-AC/Marlin-AC/tree/1.1.x-AC/documentation for: + * - Definition of the matrix scaling parameters + * - Matrices for 4 and 7 point calibration */ - #define ZP(N,I) ((N) * z_at_pt[I] / 4.0f) // 4.0 = divider to normalize to integers + #define ZP(N,I) ((N) * z_at_pt[I] * 0.25f) // 4.0 = divider to normalize to integers #define Z12(I) ZP(12, I) #define Z4(I) ZP(4, I) #define Z2(I) ZP(2, I) #define Z1(I) ZP(1, I) #define Z0(I) ZP(0, I) - // calculate factors + // Calculate factors if (_7p_9_center) dcr *= 0.9f; h_factor = auto_tune_h(dcr); r_factor = auto_tune_r(dcr); @@ -552,22 +543,22 @@ void GcodeSuite::G33() { switch (probe_points) { case 0: - test_precision = 0.0f; // forced end + test_precision = 0.0f; // Forced end break; case 1: - test_precision = 0.0f; // forced end + test_precision = 0.0f; // Forced end LOOP_NUM_AXES(axis) e_delta[axis] = +Z4(CEN); break; case 2: - if (towers_set) { // see 4 point calibration (towers) matrix + if (towers_set) { // See 4 point calibration (towers) matrix e_delta.set((+Z4(__A) -Z2(__B) -Z2(__C)) * h_factor +Z4(CEN), (-Z2(__A) +Z4(__B) -Z2(__C)) * h_factor +Z4(CEN), (-Z2(__A) -Z2(__B) +Z4(__C)) * h_factor +Z4(CEN)); r_delta = (+Z4(__A) +Z4(__B) +Z4(__C) -Z12(CEN)) * r_factor; } - else { // see 4 point calibration (opposites) matrix + else { // See 4 point calibration (opposites) matrix e_delta.set((-Z4(_BC) +Z2(_CA) +Z2(_AB)) * h_factor +Z4(CEN), (+Z2(_BC) -Z4(_CA) +Z2(_AB)) * h_factor +Z4(CEN), (+Z2(_BC) +Z2(_CA) -Z4(_AB)) * h_factor +Z4(CEN)); @@ -575,13 +566,13 @@ void GcodeSuite::G33() { } break; - default: // see 7 point calibration (towers & opposites) matrix + default: // See 7 point calibration (towers & opposites) matrix e_delta.set((+Z2(__A) -Z1(__B) -Z1(__C) -Z2(_BC) +Z1(_CA) +Z1(_AB)) * h_factor +Z4(CEN), (-Z1(__A) +Z2(__B) -Z1(__C) +Z1(_BC) -Z2(_CA) +Z1(_AB)) * h_factor +Z4(CEN), (-Z1(__A) -Z1(__B) +Z2(__C) +Z1(_BC) +Z1(_CA) -Z2(_AB)) * h_factor +Z4(CEN)); r_delta = (+Z2(__A) +Z2(__B) +Z2(__C) +Z2(_BC) +Z2(_CA) +Z2(_AB) -Z12(CEN)) * r_factor; - if (towers_set) { // see 7 point tower angle calibration (towers & opposites) matrix + if (towers_set) { // See 7 point tower angle calibration (towers & opposites) matrix t_delta.set((+Z0(__A) -Z4(__B) +Z4(__C) +Z0(_BC) -Z4(_CA) +Z4(_AB) +Z0(CEN)) * a_factor, (+Z4(__A) +Z0(__B) -Z4(__C) +Z4(_BC) +Z0(_CA) -Z4(_AB) +Z0(CEN)) * a_factor, (-Z4(__A) +Z4(__B) +Z0(__C) -Z4(_BC) +Z4(_CA) +Z0(_AB) +Z0(CEN)) * a_factor); @@ -593,14 +584,14 @@ void GcodeSuite::G33() { delta_tower_angle_trim += t_delta; } else if (zero_std_dev >= test_precision) { - // roll back + // Roll back delta_endstop_adj = e_old; delta_radius = r_old; delta_height = h_old; delta_tower_angle_trim = a_old; } - if (verbose_level != 0) { // !dry run + if (verbose_level != 0) { // !Dry-run // Normalize angles to least-squares if (_angle_results) { @@ -609,7 +600,7 @@ void GcodeSuite::G33() { LOOP_NUM_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f; } - // adjust delta_height and endstops by the max amount + // Adjust delta_height and endstops by the max amount const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c); delta_height -= z_temp; LOOP_NUM_AXES(axis) delta_endstop_adj[axis] -= z_temp; @@ -617,7 +608,7 @@ void GcodeSuite::G33() { recalc_delta_settings(); NOMORE(zero_std_dev_min, zero_std_dev); - // print report + // Print report if (verbose_level == 3 || verbose_level == 0) { print_calibration_results(z_at_pt, _tower_results, _opposite_results); @@ -631,7 +622,7 @@ void GcodeSuite::G33() { #endif } - if (verbose_level != 0) { // !dry run + if (verbose_level != 0) { // !Dry-run if ((zero_std_dev >= test_precision && iterations > force_iterations) || zero_std_dev <= calibration_precision) { // end iterations SERIAL_ECHOPGM("Calibration OK"); SERIAL_ECHO_SP(32); @@ -641,53 +632,50 @@ void GcodeSuite::G33() { else #endif { - SERIAL_ECHOPAIR_F("std dev:", zero_std_dev_min, 3); + SERIAL_ECHOPGM("std dev:", p_float_t(zero_std_dev_min, 3)); } SERIAL_EOL(); - char mess[21]; - strcpy_P(mess, PSTR("Calibration sd:")); + + MString<21> msg(F("Calibration sd:")); if (zero_std_dev_min < 1) - sprintf_P(&mess[15], PSTR("0.%03i"), (int)LROUND(zero_std_dev_min * 1000.0f)); + msg.appendf(F("0.%03i"), (int)LROUND(zero_std_dev_min * 1000.0f)); else - sprintf_P(&mess[15], PSTR("%03i.x"), (int)LROUND(zero_std_dev_min)); - ui.set_status(mess); + msg.appendf(F("%03i.x"), (int)LROUND(zero_std_dev_min)); + ui.set_status(msg); print_calibration_settings(_endstop_results, _angle_results); SERIAL_ECHOLNPGM("Save with M500 and/or copy to Configuration.h"); } else { // !end iterations - char mess[15]; + SString<15> msg; if (iterations < 31) - sprintf_P(mess, PSTR("Iteration : %02i"), (unsigned int)iterations); + msg.setf(F("Iteration : %02i"), (unsigned int)iterations); else - strcpy_P(mess, PSTR("No convergence")); - SERIAL_ECHO(mess); + msg.set(F("No convergence")); + msg.echo(); SERIAL_ECHO_SP(32); - SERIAL_ECHOLNPAIR_F("std dev:", zero_std_dev, 3); - ui.set_status(mess); + SERIAL_ECHOLNPGM("std dev:", p_float_t(zero_std_dev, 3)); + ui.set_status(msg); if (verbose_level > 1) print_calibration_settings(_endstop_results, _angle_results); } } - else { // dry run + else { // Dry-run FSTR_P const enddryrun = F("End DRY-RUN"); - SERIAL_ECHOF(enddryrun); + SERIAL_ECHO(enddryrun); SERIAL_ECHO_SP(35); - SERIAL_ECHOLNPAIR_F("std dev:", zero_std_dev, 3); - - char mess[21]; - strcpy_P(mess, FTOP(enddryrun)); - strcpy_P(&mess[11], PSTR(" sd:")); + SERIAL_ECHOLNPGM("std dev:", p_float_t(zero_std_dev, 3)); + MString<30> msg(enddryrun, F(" sd:")); if (zero_std_dev < 1) - sprintf_P(&mess[15], PSTR("0.%03i"), (int)LROUND(zero_std_dev * 1000.0f)); + msg.appendf(F("0.%03i"), (int)LROUND(zero_std_dev * 1000.0f)); else - sprintf_P(&mess[15], PSTR("%03i.x"), (int)LROUND(zero_std_dev)); - ui.set_status(mess); + msg.appendf(F("%03i.x"), (int)LROUND(zero_std_dev)); + ui.set_status(msg); } ac_home(); } while (((zero_std_dev < test_precision && iterations < 31) || iterations <= force_iterations) && zero_std_dev > calibration_precision); - ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index)); + ac_cleanup(); TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); #if HAS_DELTA_SENSORLESS_PROBING diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 1be3952ffe..504dcd1c6f 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -39,6 +39,25 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" +/** + * G34: Mechanical Gantry Calibration + * + * Align the ends of the X gantry. See https://youtu.be/3jAFQdTk8iw + * + * - The carriage moves to GANTRY_CALIBRATION_SAFE_POSITION, also called the “pounce†position. + * - If possible, the Z stepper current is reduced to the value specified by 'S' + * (or GANTRY_CALIBRATION_CURRENT) to prevent damage to steppers and other parts. + * The reduced current should be just high enough to move the Z axis when not blocked. + * - The Z axis is jogged past the Z limit, only as far as the specified Z distance + * (or GANTRY_CALIBRATION_EXTRA_HEIGHT) at the GANTRY_CALIBRATION_FEEDRATE. + * - The Z axis is moved back to the working area (also at GANTRY_CALIBRATION_FEEDRATE). + * - Stepper current is restored back to normal. + * - The machine is re-homed, according to GANTRY_CALIBRATION_COMMANDS_POST. + * + * Parameters: + * S Current value to use for the raise move. (Default: GANTRY_CALIBRATION_CURRENT) + * Z Extra distance past Z_MAX_POS to move the Z axis. (Default: GANTRY_CALIBRATION_EXTRA_HEIGHT) + */ void GcodeSuite::G34() { // Home before the alignment procedure @@ -58,7 +77,7 @@ void GcodeSuite::G34() { // Move XY to safe position if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Parking XY"); const xy_pos_t safe_pos = GANTRY_CALIBRATION_SAFE_POSITION; - do_blocking_move_to(safe_pos, MMM_TO_MMS(GANTRY_CALIBRATION_XY_PARK_FEEDRATE)); + do_blocking_move_to_xy(safe_pos, MMM_TO_MMS(GANTRY_CALIBRATION_XY_PARK_FEEDRATE)); #endif const float move_distance = parser.intval('Z', GANTRY_CALIBRATION_EXTRA_HEIGHT), @@ -78,37 +97,36 @@ void GcodeSuite::G34() { #if HAS_MOTOR_CURRENT_SPI const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT); - const uint32_t previous_current = stepper.motor_current_setting[Z_AXIS]; + const uint32_t previous_current_Z = stepper.motor_current_setting[Z_AXIS]; stepper.set_digipot_current(Z_AXIS, target_current); #elif HAS_MOTOR_CURRENT_PWM const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT); - const uint32_t previous_current = stepper.motor_current_setting[1]; // Z + const uint32_t previous_current_Z = stepper.motor_current_setting[1]; // Z stepper.set_digipot_current(1, target_current); #elif HAS_MOTOR_CURRENT_DAC const float target_current = parser.floatval('S', GANTRY_CALIBRATION_CURRENT); - const float previous_current = dac_amps(Z_AXIS, target_current); + const float previous_current_Z = dac_amps(Z_AXIS, target_current); stepper_dac.set_current_value(Z_AXIS, target_current); #elif HAS_MOTOR_CURRENT_I2C const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT); - previous_current = dac_amps(Z_AXIS); + const float previous_current_Z = dac_amps(Z_AXIS); 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_STEPPERS]; - #if AXIS_IS_TMC(Z) - previous_current_arr[0] = stepperZ.getMilliamps(); + #if Z_IS_TRINAMIC + static uint16_t previous_current_Z = stepperZ.getMilliamps(); stepperZ.rms_current(target_current); #endif - #if AXIS_IS_TMC(Z2) - previous_current_arr[1] = stepperZ2.getMilliamps(); + #if Z2_IS_TRINAMIC + static uint16_t previous_current_Z2 = stepperZ2.getMilliamps(); stepperZ2.rms_current(target_current); #endif - #if AXIS_IS_TMC(Z3) - previous_current_arr[2] = stepperZ3.getMilliamps(); + #if Z3_IS_TRINAMIC + static uint16_t previous_current_Z3 = stepperZ3.getMilliamps(); stepperZ3.rms_current(target_current); #endif - #if AXIS_IS_TMC(Z4) - previous_current_arr[3] = stepperZ4.getMilliamps(); + #if Z4_IS_TRINAMIC + static uint16_t previous_current_Z4 = stepperZ4.getMilliamps(); stepperZ4.rms_current(target_current); #endif #endif @@ -123,26 +141,18 @@ void GcodeSuite::G34() { #endif #if HAS_MOTOR_CURRENT_SPI - stepper.set_digipot_current(Z_AXIS, previous_current); + stepper.set_digipot_current(Z_AXIS, previous_current_Z); #elif HAS_MOTOR_CURRENT_PWM - stepper.set_digipot_current(1, previous_current); + stepper.set_digipot_current(1, previous_current_Z); #elif HAS_MOTOR_CURRENT_DAC - stepper_dac.set_current_value(Z_AXIS, previous_current); + stepper_dac.set_current_value(Z_AXIS, previous_current_Z); #elif HAS_MOTOR_CURRENT_I2C - digipot_i2c.set_current(Z_AXIS, previous_current) + digipot_i2c.set_current(Z_AXIS, previous_current_Z) #elif HAS_TRINAMIC_CONFIG - #if AXIS_IS_TMC(Z) - stepperZ.rms_current(previous_current_arr[0]); - #endif - #if AXIS_IS_TMC(Z2) - stepperZ2.rms_current(previous_current_arr[1]); - #endif - #if AXIS_IS_TMC(Z3) - stepperZ3.rms_current(previous_current_arr[2]); - #endif - #if AXIS_IS_TMC(Z4) - stepperZ4.rms_current(previous_current_arr[3]); - #endif + TERN_(Z_IS_TRINAMIC, stepperZ.rms_current(previous_current_Z)); + TERN_(Z2_IS_TRINAMIC, stepperZ2.rms_current(previous_current_Z2)); + TERN_(Z3_IS_TRINAMIC, stepperZ3.rms_current(previous_current_Z3)); + TERN_(Z4_IS_TRINAMIC, stepperZ4.rms_current(previous_current_Z4)); #endif // Back off end plate, back to normal motion range diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 8cf652cd84..6c367ad882 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) +#if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) #include "../../feature/z_stepper_align.h" @@ -37,10 +37,6 @@ #include "../../feature/bedlevel/bedlevel.h" #endif -#if HAS_MULTI_HOTEND - #include "../../module/tool_change.h" -#endif - #if HAS_Z_STEPPER_ALIGN_STEPPER_XY #include "../../libs/least_squares_fit.h" #endif @@ -60,25 +56,27 @@ #endif /** - * G34: Z-Stepper automatic alignment + * G34: Z Steppers Auto-Alignment * - * Manual stepper lock controls (reset by G28): - * L Unlock all steppers - * Z<1-4> Z stepper to lock / unlock - * S 0=UNLOCKED 1=LOCKED. If omitted, assume LOCKED. + * Parameters: + * Manual stepper lock controls (reset by G28): + * L Unlock all steppers + * Z Target specific Z stepper to lock/unlock (1-4) + * S Lock state; 0=UNLOCKED 1=LOCKED. If omitted, assume LOCKED * - * Examples: - * G34 Z1 ; Lock Z1 - * G34 L Z2 ; Unlock all, then lock Z2 - * G34 Z2 S0 ; Unlock Z2 + * With Z_STEPPER_AUTO_ALIGN: + * I Number of test iterations. If omitted, Z_STEPPER_ALIGN_ITERATIONS. (1-30) + * T Target Accuracy factor. If omitted, Z_STEPPER_ALIGN_ACC. (0.01-1.0) + * A Provide an Amplification value. If omitted, Z_STEPPER_ALIGN_AMP. (0.5-2.0) + * R Recalculate points based on current probe offsets * - * With Z_STEPPER_AUTO_ALIGN: - * I Number of tests. If omitted, Z_STEPPER_ALIGN_ITERATIONS. - * T Target Accuracy factor. If omitted, Z_STEPPER_ALIGN_ACC. - * A Provide an Amplification value. If omitted, Z_STEPPER_ALIGN_AMP. - * R Flag to recalculate points based on current probe offsets + * Example: + * G34 Z1 ; Lock Z1 + * G34 L Z2 ; Unlock all, then lock Z2 + * G34 Z2 S0 ; Unlock Z2 */ void GcodeSuite::G34() { + DEBUG_SECTION(log_G34, "G34", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); @@ -108,23 +106,24 @@ void GcodeSuite::G34() { } #if ENABLED(Z_STEPPER_AUTO_ALIGN) + do { // break out on error const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS); if (!WITHIN(z_auto_align_iterations, 1, 30)) { - SERIAL_ECHOLNPGM("?(I)teration out of bounds (1-30)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(I)teration out of bounds (1-30).")); break; } const float z_auto_align_accuracy = parser.floatval('T', Z_STEPPER_ALIGN_ACC); - if (!WITHIN(z_auto_align_accuracy, 0.01f, 1.0f)) { - SERIAL_ECHOLNPGM("?(T)arget accuracy out of bounds (0.01-1.0)."); + if (!WITHIN(z_auto_align_accuracy, 0.001f, 1.0f)) { + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(T)arget accuracy out of bounds (0.001-1.0).")); break; } const float z_auto_align_amplification = TERN(HAS_Z_STEPPER_ALIGN_STEPPER_XY, Z_STEPPER_ALIGN_AMP, parser.floatval('A', Z_STEPPER_ALIGN_AMP)); if (!WITHIN(ABS(z_auto_align_amplification), 0.5f, 2.0f)) { - SERIAL_ECHOLNPGM("?(A)mplification out of bounds (0.5-2.0)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(A)mplification out of bounds (0.5-2.0).")); break; } @@ -142,26 +141,23 @@ void GcodeSuite::G34() { TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); - // Always home with tool 0 active - #if HAS_MULTI_HOTEND - const uint8_t old_tool_index = active_extruder; - tool_change(0, true); + probe.use_probing_tool(); + + #ifdef EVENT_GCODE_BEFORE_G34 + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Before G34 G-code: ", F(EVENT_GCODE_BEFORE_G34)); + gcode.process_subcommands_now(F(EVENT_GCODE_BEFORE_G34)); #endif TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); - // In BLTOUCH HS mode, the probe travels in a deployed state. - // Users of G34 might have a badly misaligned bed, so raise Z by the - // length of the deployed pin (BLTOUCH stroke < 7mm) - #define Z_BASIC_CLEARANCE (Z_CLEARANCE_BETWEEN_PROBES + TERN0(BLTOUCH, bltouch.z_extra_clearance())) - // Compute a worst-case clearance height to probe from. After the first // iteration this will be re-calculated based on the actual bed position auto magnitude2 = [&](const uint8_t i, const uint8_t j) { const xy_pos_t diff = z_stepper_align.xy[i] - z_stepper_align.xy[j]; return HYPOT2(diff.x, diff.y); }; - float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * SQRT(_MAX(0, magnitude2(0, 1) + const float zoffs = (probe.offset.z < 0) ? -probe.offset.z : 0.0f; + float z_probe = (Z_TWEEN_SAFE_CLEARANCE + zoffs) + (G34_MAX_GRADE) * 0.01f * SQRT(_MAX(0, magnitude2(0, 1) #if TRIPLE_Z , magnitude2(2, 1), magnitude2(2, 0) #if QUAD_Z @@ -173,12 +169,6 @@ void GcodeSuite::G34() { // Home before the alignment procedure home_if_needed(); - // Move the Z coordinate realm towards the positive - dirty trick - current_position.z += z_probe * 0.5f; - sync_plan_position(); - // Now, the Z origin lies below the build plate. That allows to probe deeper, before run_z_probe throws an error. - // This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration. - #if !HAS_Z_STEPPER_ALIGN_STEPPER_XY float last_z_align_move[NUM_Z_STEPPERS] = ARRAY_N_1(NUM_Z_STEPPERS, 10000.0f); #else @@ -217,24 +207,40 @@ void GcodeSuite::G34() { float z_measured_max = -100000.0f; // Probe all positions (one per Z-Stepper) - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { // iteration odd/even --> downward / upward stepper sequence const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPERS - 1 - i : i; - // Safe clearance even on an incline - if ((iteration == 0 || i > 0) && z_probe > current_position.z) do_blocking_move_to_z(z_probe); - xy_pos_t &ppos = z_stepper_align.xy[iprobe]; - if (DEBUGGING(LEVELING)) - DEBUG_ECHOLNPGM_P(PSTR("Probing X"), ppos.x, SP_Y_STR, ppos.y); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM_P(PSTR("Probing X"), ppos.x, SP_Y_STR, ppos.y); // Probe a Z height for each stepper. // Probing sanity check is disabled, as it would trigger even in normal cases because // current_position.z has been manually altered in the "dirty trick" above. - const float z_probed_height = probe.probe_at_point(DIFF_TERN(HAS_HOME_OFFSET, ppos, xy_pos_t(home_offset)), raise_after, 0, true, false); + + const float minz = (Z_PROBE_LOW_POINT) - (z_probe * 0.5f); + + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOPGM("Z_PROBE_LOW_POINT: " STRINGIFY(Z_PROBE_LOW_POINT)); + DEBUG_ECHOLNPGM(" z_probe: ", p_float_t(z_probe, 3), + " Probe Tgt: ", p_float_t(minz, 3)); + } + + const float z_probed_height = probe.probe_at_point( + DIFF_TERN(HAS_HOME_OFFSET, ppos, xy_pos_t(home_offset)), // xy + raise_after, // raise_after + (DEBUGGING(LEVELING) || DEBUGGING(INFO)) ? 3 : 0, // verbose_level + true, false, // probe_relative, sanity_check + minz, // z_min_point + Z_TWEEN_SAFE_CLEARANCE // z_clearance + ); + + if (DEBUGGING(LEVELING)) + DEBUG_ECHOLN(F("Probing X"), ppos.x, FPSTR(SP_Y_STR), ppos.y, F(" Height = "), z_probed_height); + if (isnan(z_probed_height)) { - SERIAL_ECHOLNPGM("Probing failed"); + SERIAL_ECHOLNPGM(STR_ERR_PROBING_FAILED); LCD_MESSAGE(MSG_LCD_PROBING_FAILED); err_break = true; break; @@ -242,7 +248,7 @@ void GcodeSuite::G34() { // Add height to each value, to provide a more useful target height for // the next iteration of probing. This allows adjustments to be made away from the bed. - z_measured[iprobe] = z_probed_height + Z_CLEARANCE_BETWEEN_PROBES; + z_measured[iprobe] = z_probed_height + (Z_TWEEN_SAFE_CLEARANCE + zoffs); //do we need to add the clearance to this? if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", iprobe + 1, " measured position is ", z_measured[iprobe]); @@ -256,7 +262,12 @@ void GcodeSuite::G34() { // Adapt the next probe clearance height based on the new measurements. // Safe_height = lowest distance to bed (= highest measurement) plus highest measured misalignment. z_maxdiff = z_measured_max - z_measured_min; - z_probe = Z_BASIC_CLEARANCE + z_measured_max + z_maxdiff; + + // The intent of the line below seems to be to clamp the probe depth on successive iterations of G34, but in reality if the amplification + // factor is not completely accurate, this was causing probing to fail as the probe stopped fractions of a mm from the trigger point + // on the second iteration very reliably. This may be restored with an uncertainty factor at some point, however its usefulness after + // all probe points have seen a successful probe is questionable. + //z_probe = (Z_TWEEN_SAFE_CLEARANCE + zoffs) + z_measured_max + z_maxdiff; // Not sure we need z_maxdiff, but leaving it in for safety. #if HAS_Z_STEPPER_ALIGN_STEPPER_XY // Replace the initial values in z_measured with calculated heights at @@ -272,14 +283,14 @@ void GcodeSuite::G34() { // This allows the actual adjustment logic to be shared by both algorithms. linear_fit_data lfd; incremental_LSF_reset(&lfd); - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { SERIAL_ECHOLNPGM("PROBEPT_", i, ": ", z_measured[i]); incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); } finish_incremental_LSF(&lfd); z_measured_min = 100000.0f; - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { z_measured[i] = -(lfd.A * z_stepper_align.stepper_xy[i].x + lfd.B * z_stepper_align.stepper_xy[i].y + lfd.D); z_measured_min = _MIN(z_measured_min, z_measured[i]); } @@ -294,44 +305,23 @@ void GcodeSuite::G34() { ); #endif - SERIAL_ECHOLNPGM("\n" - "Z2-Z1=", ABS(z_measured[1] - z_measured[0]) - #if TRIPLE_Z - , " Z3-Z2=", ABS(z_measured[2] - z_measured[1]) - , " Z3-Z1=", ABS(z_measured[2] - z_measured[0]) - #if QUAD_Z - , " Z4-Z3=", ABS(z_measured[3] - z_measured[2]) - , " Z4-Z2=", ABS(z_measured[3] - z_measured[1]) - , " Z4-Z1=", ABS(z_measured[3] - z_measured[0]) - #endif - #endif - ); + SERIAL_EOL(); - #if HAS_STATUS_MESSAGE - char fstr1[10]; - char msg[6 + (6 + 5) * NUM_Z_STEPPERS + 1] - #if TRIPLE_Z - , fstr2[10], fstr3[10] - #if QUAD_Z - , fstr4[10], fstr5[10], fstr6[10] - #endif - #endif - ; - sprintf_P(msg, - PSTR("1:2=%s" TERN_(TRIPLE_Z, " 3-2=%s 3-1=%s") TERN_(QUAD_Z, " 4-3=%s 4-2=%s 4-1=%s")), - dtostrf(ABS(z_measured[1] - z_measured[0]), 1, 3, fstr1) - OPTARG(TRIPLE_Z, - dtostrf(ABS(z_measured[2] - z_measured[1]), 1, 3, fstr2), - dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3)) - OPTARG(QUAD_Z, - dtostrf(ABS(z_measured[3] - z_measured[2]), 1, 3, fstr4), - dtostrf(ABS(z_measured[3] - z_measured[1]), 1, 3, fstr5), - dtostrf(ABS(z_measured[3] - z_measured[0]), 1, 3, fstr6)) - ); - ui.set_status(msg); + SString<15 + TERN0(TRIPLE_Z, 30) + TERN0(QUAD_Z, 45)> msg(F("2-1="), p_float_t(ABS(z_measured[1] - z_measured[0]), 3)); + #if TRIPLE_Z + msg.append(F(" 3-2="), p_float_t(ABS(z_measured[2] - z_measured[1]), 3)) + .append(F(" 3-1="), p_float_t(ABS(z_measured[2] - z_measured[0]), 3)); + #endif + #if QUAD_Z + msg.append(F(" 4-3="), p_float_t(ABS(z_measured[3] - z_measured[2]), 3)) + .append(F(" 4-2="), p_float_t(ABS(z_measured[3] - z_measured[1]), 3)) + .append(F(" 4-1="), p_float_t(ABS(z_measured[3] - z_measured[0]), 3)); #endif - auto decreasing_accuracy = [](const_float_t v1, const_float_t v2) { + msg.echoln(); + ui.set_status(msg); + + auto decreasing_accuracy = [](const float v1, const float v2) { if (v1 < v2 * 0.7f) { SERIAL_ECHOLNPGM("Decreasing Accuracy Detected."); LCD_MESSAGE(MSG_DECREASING_ACCURACY); @@ -347,12 +337,12 @@ void GcodeSuite::G34() { // Calculate mean value as a reference float z_measured_mean = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPERS) z_measured_mean += z_measured[zstepper]; + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) z_measured_mean += z_measured[zstepper]; z_measured_mean /= NUM_Z_STEPPERS; // Calculate the sum of the absolute deviations from the mean value float z_align_level_indicator = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPERS) + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) z_align_level_indicator += ABS(z_measured[zstepper] - z_measured_mean); // If it's getting worse, stop and throw an error @@ -367,7 +357,7 @@ void GcodeSuite::G34() { bool success_break = true; // Correct the individual stepper offsets - LOOP_L_N(zstepper, NUM_Z_STEPPERS) { + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) { // Calculate current stepper move float z_align_move = z_measured[zstepper] - z_measured_min; const float z_align_abs = ABS(z_align_move); @@ -380,7 +370,7 @@ void GcodeSuite::G34() { if (decreasing_accuracy(last_z_align_move[zstepper], z_align_abs)) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", zstepper + 1, " last_z_align_move = ", last_z_align_move[zstepper]); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", zstepper + 1, " z_align_abs = ", z_align_abs); - adjustment_reverse = !adjustment_reverse; + FLIP(adjustment_reverse); } // Remember the alignment for the next iteration, but only if steppers move, @@ -400,7 +390,7 @@ void GcodeSuite::G34() { // Decreasing accuracy was detected so move was inverted. // Will match reversed Z steppers on dual steppers. Triple will need more work to map. if (adjustment_reverse) { - z_align_move = -z_align_move; + z_align_move *= -1; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", zstepper + 1, " correction reversed to ", z_align_move); } #endif @@ -428,7 +418,7 @@ void GcodeSuite::G34() { SERIAL_ECHOLNPGM("G34 aborted."); else { SERIAL_ECHOLNPGM("Did ", iteration + (iteration != z_auto_align_iterations), " of ", z_auto_align_iterations); - SERIAL_ECHOLNPAIR_F("Accuracy: ", z_maxdiff); + SERIAL_ECHOLNPGM("Accuracy: ", p_float_t(z_maxdiff, 3)); } // Stow the probe because the last call to probe.probe_at_point(...) @@ -436,26 +426,40 @@ void GcodeSuite::G34() { IF_DISABLED(TOUCH_MI_PROBE, probe.stow()); #if ENABLED(HOME_AFTER_G34) - // After this operation the z position needs correction - set_axis_never_homed(Z_AXIS); // Home Z after the alignment procedure process_subcommands_now(F("G28Z")); #else // Use the probed height from the last iteration to determine the Z height. // z_measured_min is used, because all steppers are aligned to z_measured_min. // Ideally, this would be equal to the 'z_probe * 0.5f' which was added earlier. - current_position.z -= z_measured_min - (float)Z_CLEARANCE_BETWEEN_PROBES; + if (DEBUGGING(LEVELING)) + DEBUG_ECHOLNPGM( + "z_measured_min: ", p_float_t(z_measured_min, 3), + "Z_TWEEN_SAFE_CLEARANCE: ", p_float_t(Z_TWEEN_SAFE_CLEARANCE, 3), + "zoffs: ", p_float_t(zoffs, 3) + ); + + if (!err_break) + current_position.z -= z_measured_min - (Z_TWEEN_SAFE_CLEARANCE + zoffs); // We shouldn't want to subtract the clearance from here right? (Depends if we added it further up) sync_plan_position(); #endif - // Restore the active tool after homing - TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER))); // Fetch previous tool for parking extruder + #ifdef EVENT_GCODE_AFTER_G34 + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("After G34 G-code: ", F(EVENT_GCODE_AFTER_G34)); + planner.synchronize(); + process_subcommands_now(F(EVENT_GCODE_AFTER_G34)); + #endif - #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34) + probe.use_probing_tool(false); + + #if ALL(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34) set_bed_leveling_enabled(leveling_was_active); #endif }while(0); + + probe.use_probing_tool(false); + #endif // Z_STEPPER_AUTO_ALIGN } @@ -491,7 +495,7 @@ void GcodeSuite::M422() { const bool is_probe_point = parser.seen_test('S'); if (TERN0(HAS_Z_STEPPER_ALIGN_STEPPER_XY, is_probe_point && parser.seen_test('W'))) { - SERIAL_ECHOLNPGM("?(S) and (W) may not be combined."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(S) and (W) may not be combined.")); return; } @@ -501,7 +505,7 @@ void GcodeSuite::M422() { ); if (!is_probe_point && TERN1(HAS_Z_STEPPER_ALIGN_STEPPER_XY, !parser.seen_test('W'))) { - SERIAL_ECHOLNPGM("?(S)" TERN_(HAS_Z_STEPPER_ALIGN_STEPPER_XY, " or (W)") " is required."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(S)" TERN_(HAS_Z_STEPPER_ALIGN_STEPPER_XY, " or (W)") " is required.")); return; } @@ -518,8 +522,7 @@ void GcodeSuite::M422() { } if (!WITHIN(position_index, 1, NUM_Z_STEPPERS)) { - SERIAL_ECHOF(err_string); - SERIAL_ECHOLNPGM(" index invalid (1.." STRINGIFY(NUM_Z_STEPPERS) ")."); + SERIAL_ECHOLN(err_string, F(" index invalid (1.." STRINGIFY(NUM_Z_STEPPERS) ").")); return; } @@ -532,11 +535,11 @@ void GcodeSuite::M422() { if (is_probe_point) { if (!probe.can_reach(pos.x, Y_CENTER)) { - SERIAL_ECHOLNPGM("?(X) out of bounds."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(X) out of bounds.")); return; } if (!probe.can_reach(pos)) { - SERIAL_ECHOLNPGM("?(Y) out of bounds."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(Y) out of bounds.")); return; } } @@ -545,8 +548,10 @@ void GcodeSuite::M422() { } void GcodeSuite::M422_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading(forReplay, F(STR_Z_AUTO_ALIGN)); - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M422 S"), i + 1, @@ -555,7 +560,7 @@ void GcodeSuite::M422_report(const bool forReplay/*=true*/) { ); } #if HAS_Z_STEPPER_ALIGN_STEPPER_XY - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M422 W"), i + 1, diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index a22608f5b4..883d7b4b6f 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -33,10 +33,13 @@ #include "../../lcd/marlinui.h" #include "../../module/motion.h" #include "../../module/planner.h" -#include "../../module/tool_change.h" #include "../../module/endstops.h" #include "../../feature/bedlevel/bedlevel.h" +#if HAS_MULTI_HOTEND + #include "../../module/tool_change.h" +#endif + #if !AXIS_CAN_CALIBRATE(X) #undef CALIBRATION_MEASURE_LEFT #undef CALIBRATION_MEASURE_RIGHT @@ -70,7 +73,7 @@ #define CALIBRATION_MEASUREMENT_CERTAIN 0.5 // mm #endif -#if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) +#if ALL(HAS_X_AXIS, CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) #define HAS_X_CENTER 1 #endif #if ALL(HAS_Y_AXIS, CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) @@ -97,7 +100,9 @@ enum side_t : uint8_t { TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES, - LIST_N(DOUBLE(SECONDARY_AXES), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM, UMINIMUM, UMAXIMUM, VMINIMUM, VMAXIMUM, WMINIMUM, WMAXIMUM) + LIST_N(DOUBLE(SECONDARY_AXES), + IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM, + UMINIMUM, UMAXIMUM, VMINIMUM, VMAXIMUM, WMINIMUM, WMAXIMUM) }; static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER; @@ -171,27 +176,13 @@ inline void park_above_object(measurements_t &m, const float uncertainty) { #if HAS_HOTEND_OFFSET inline void normalize_hotend_offsets() { - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) hotend_offset[e] -= hotend_offset[0]; hotend_offset[0].reset(); } #endif -#if !PIN_EXISTS(CALIBRATION) - #include "../../module/probe.h" -#endif - -inline bool read_calibration_pin() { - return ( - #if PIN_EXISTS(CALIBRATION) - READ(CALIBRATION_PIN) != CALIBRATION_PIN_INVERTING - #else - PROBE_TRIGGERED() - #endif - ); -} - /** * Move along axis in the specified dir until the probe value becomes stop_state, * then return the axis value. @@ -202,18 +193,18 @@ inline bool read_calibration_pin() { * fast in - Fast vs. precise measurement */ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_state, const bool fast) { - const float step = fast ? 0.25 : CALIBRATION_MEASUREMENT_RESOLUTION; const feedRate_t mms = fast ? MMM_TO_MMS(CALIBRATION_FEEDRATE_FAST) : MMM_TO_MMS(CALIBRATION_FEEDRATE_SLOW); const float limit = fast ? 50 : 5; destination = current_position; - for (float travel = 0; travel < limit; travel += step) { - destination[axis] += dir * step; - do_blocking_move_to((xyz_pos_t)destination, mms); - planner.synchronize(); - if (read_calibration_pin() == stop_state) break; - } - return destination[axis]; + destination[axis] += dir * limit; + endstops.enable_calibration_probe(true, stop_state); + do_blocking_move_to((xyz_pos_t)destination, mms); + endstops.enable_calibration_probe(false); + endstops.hit_on_purpose(); + set_current_from_steppers_for_axis(axis); + sync_plan_position(); + return current_position[axis]; } /** @@ -271,10 +262,10 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t #if AXIS_CAN_CALIBRATE(X) _ACASE(X, RIGHT, LEFT); #endif - #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) + #if AXIS_CAN_CALIBRATE(Y) _ACASE(Y, BACK, FRONT); #endif - #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(Z) case TOP: { const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); m.obj_center.z = measurement - dimensions.z / 2; @@ -282,22 +273,22 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t return; } #endif - #if HAS_I_AXIS && AXIS_CAN_CALIBRATE(I) + #if AXIS_CAN_CALIBRATE(I) _PCASE(I); #endif - #if HAS_J_AXIS && AXIS_CAN_CALIBRATE(J) + #if AXIS_CAN_CALIBRATE(J) _PCASE(J); #endif - #if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K) + #if AXIS_CAN_CALIBRATE(K) _PCASE(K); #endif - #if HAS_U_AXIS && AXIS_CAN_CALIBRATE(U) + #if AXIS_CAN_CALIBRATE(U) _PCASE(U); #endif - #if HAS_V_AXIS && AXIS_CAN_CALIBRATE(V) + #if AXIS_CAN_CALIBRATE(V) _PCASE(V); #endif - #if HAS_W_AXIS && AXIS_CAN_CALIBRATE(W) + #if AXIS_CAN_CALIBRATE(W) _PCASE(W); #endif default: return; @@ -343,10 +334,22 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { probe_side(m, uncertainty, TOP); #endif - TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); + /** + * Allow Y axis to probe and compute values before X axis (or remaining arbitrary axes) + * to assist with centering in calibration object. Lulzbot saw issues with higher uncertainty + * values where the nozzle was catching on the edges of the cube, and this was intended to help + * ensure the probe object remained centered. + */ TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge)); + + #if HAS_Y_CENTER + m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2; + m.nozzle_outer_dimension.y = m.obj_side[BACK] - m.obj_side[FRONT] - dimensions.y; + #endif + + TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); TERN_(CALIBRATION_MEASURE_IMIN, probe_side(m, uncertainty, IMINIMUM, probe_top_at_edge)); TERN_(CALIBRATION_MEASURE_IMAX, probe_side(m, uncertainty, IMAXIMUM, probe_top_at_edge)); TERN_(CALIBRATION_MEASURE_JMIN, probe_side(m, uncertainty, JMINIMUM, probe_top_at_edge)); @@ -362,7 +365,6 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // Compute the measured center of the calibration object. TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2); - TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2); TERN_(HAS_I_CENTER, m.obj_center.i = (m.obj_side[IMINIMUM] + m.obj_side[IMAXIMUM]) / 2); TERN_(HAS_J_CENTER, m.obj_center.j = (m.obj_side[JMINIMUM] + m.obj_side[JMAXIMUM]) / 2); TERN_(HAS_K_CENTER, m.obj_center.k = (m.obj_side[KMINIMUM] + m.obj_side[KMAXIMUM]) / 2); @@ -373,7 +375,6 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // Compute the outside diameter of the nozzle at the height // at which it makes contact with the calibration object TERN_(HAS_X_CENTER, m.nozzle_outer_dimension.x = m.obj_side[RIGHT] - m.obj_side[LEFT] - dimensions.x); - TERN_(HAS_Y_CENTER, m.nozzle_outer_dimension.y = m.obj_side[BACK] - m.obj_side[FRONT] - dimensions.y); park_above_object(m, uncertainty); @@ -395,14 +396,16 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if ENABLED(CALIBRATION_REPORTING) inline void report_measured_faces(const measurements_t &m) { SERIAL_ECHOLNPGM("Sides:"); - #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPGM(" Top: ", m.obj_side[TOP]); #endif - #if ENABLED(CALIBRATION_MEASURE_LEFT) - SERIAL_ECHOLNPGM(" Left: ", m.obj_side[LEFT]); - #endif - #if ENABLED(CALIBRATION_MEASURE_RIGHT) - SERIAL_ECHOLNPGM(" Right: ", m.obj_side[RIGHT]); + #if HAS_X_AXIS + #if ENABLED(CALIBRATION_MEASURE_LEFT) + SERIAL_ECHOLNPGM(" Left: ", m.obj_side[LEFT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_RIGHT) + SERIAL_ECHOLNPGM(" Right: ", m.obj_side[RIGHT]); + #endif #endif #if HAS_Y_AXIS #if ENABLED(CALIBRATION_MEASURE_FRONT) @@ -465,102 +468,54 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { inline void report_measured_center(const measurements_t &m) { SERIAL_ECHOLNPGM("Center:"); - #if HAS_X_CENTER - SERIAL_ECHOLNPGM_P(SP_X_STR, m.obj_center.x); - #endif - #if HAS_Y_CENTER - SERIAL_ECHOLNPGM_P(SP_Y_STR, m.obj_center.y); - #endif + TERF(HAS_X_CENTER, SERIAL_ECHOLNPGM_P)(SP_X_STR, m.obj_center.x); + TERF(HAS_Y_CENTER, SERIAL_ECHOLNPGM_P)(SP_Y_STR, m.obj_center.y); SERIAL_ECHOLNPGM_P(SP_Z_STR, m.obj_center.z); - #if HAS_I_CENTER - SERIAL_ECHOLNPGM_P(SP_I_STR, m.obj_center.i); - #endif - #if HAS_J_CENTER - SERIAL_ECHOLNPGM_P(SP_J_STR, m.obj_center.j); - #endif - #if HAS_K_CENTER - SERIAL_ECHOLNPGM_P(SP_K_STR, m.obj_center.k); - #endif - #if HAS_U_CENTER - SERIAL_ECHOLNPGM_P(SP_U_STR, m.obj_center.u); - #endif - #if HAS_V_CENTER - SERIAL_ECHOLNPGM_P(SP_V_STR, m.obj_center.v); - #endif - #if HAS_W_CENTER - SERIAL_ECHOLNPGM_P(SP_W_STR, m.obj_center.w); - #endif + TERF(HAS_I_CENTER, SERIAL_ECHOLNPGM_P)(SP_I_STR, m.obj_center.i); + TERF(HAS_J_CENTER, SERIAL_ECHOLNPGM_P)(SP_J_STR, m.obj_center.j); + TERF(HAS_K_CENTER, SERIAL_ECHOLNPGM_P)(SP_K_STR, m.obj_center.k); + TERF(HAS_U_CENTER, SERIAL_ECHOLNPGM_P)(SP_U_STR, m.obj_center.u); + TERF(HAS_V_CENTER, SERIAL_ECHOLNPGM_P)(SP_V_STR, m.obj_center.v); + TERF(HAS_W_CENTER, SERIAL_ECHOLNPGM_P)(SP_W_STR, m.obj_center.w); SERIAL_EOL(); } inline void report_measured_backlash(const measurements_t &m) { SERIAL_ECHOLNPGM("Backlash:"); #if AXIS_CAN_CALIBRATE(X) - #if ENABLED(CALIBRATION_MEASURE_LEFT) - SERIAL_ECHOLNPGM(" Left: ", m.backlash[LEFT]); - #endif - #if ENABLED(CALIBRATION_MEASURE_RIGHT) - SERIAL_ECHOLNPGM(" Right: ", m.backlash[RIGHT]); - #endif + TERF(CALIBRATION_MEASURE_LEFT, SERIAL_ECHOLNPGM)(" Left: ", m.backlash[LEFT]); + TERF(CALIBRATION_MEASURE_RIGHT, SERIAL_ECHOLNPGM)(" Right: ", m.backlash[RIGHT]); #endif - #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) - #if ENABLED(CALIBRATION_MEASURE_FRONT) - SERIAL_ECHOLNPGM(" Front: ", m.backlash[FRONT]); - #endif - #if ENABLED(CALIBRATION_MEASURE_BACK) - SERIAL_ECHOLNPGM(" Back: ", m.backlash[BACK]); - #endif + #if AXIS_CAN_CALIBRATE(Y) + TERF(CALIBRATION_MEASURE_FRONT, SERIAL_ECHOLNPGM)(" Front: ", m.backlash[FRONT]); + TERF(CALIBRATION_MEASURE_BACK, SERIAL_ECHOLNPGM)(" Back: ", m.backlash[BACK]); #endif - #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPGM(" Top: ", m.backlash[TOP]); #endif - #if HAS_I_AXIS && AXIS_CAN_CALIBRATE(I) - #if ENABLED(CALIBRATION_MEASURE_IMIN) - SERIAL_ECHOLNPGM(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); - #endif - #if ENABLED(CALIBRATION_MEASURE_IMAX) - SERIAL_ECHOLNPGM(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); - #endif + #if AXIS_CAN_CALIBRATE(I) + TERF(CALIBRATION_MEASURE_IMIN, SERIAL_ECHOLNPGM)(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); + TERF(CALIBRATION_MEASURE_IMAX, SERIAL_ECHOLNPGM)(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); #endif - #if HAS_J_AXIS && AXIS_CAN_CALIBRATE(J) - #if ENABLED(CALIBRATION_MEASURE_JMIN) - SERIAL_ECHOLNPGM(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); - #endif - #if ENABLED(CALIBRATION_MEASURE_JMAX) - SERIAL_ECHOLNPGM(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); - #endif + #if AXIS_CAN_CALIBRATE(J) + TERF(CALIBRATION_MEASURE_JMIN, SERIAL_ECHOLNPGM)(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); + TERF(CALIBRATION_MEASURE_JMAX, SERIAL_ECHOLNPGM)(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); #endif - #if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K) - #if ENABLED(CALIBRATION_MEASURE_KMIN) - SERIAL_ECHOLNPGM(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); - #endif - #if ENABLED(CALIBRATION_MEASURE_KMAX) - SERIAL_ECHOLNPGM(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]); - #endif + #if AXIS_CAN_CALIBRATE(K) + TERF(CALIBRATION_MEASURE_KMIN, SERIAL_ECHOLNPGM)(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); + TERF(CALIBRATION_MEASURE_KMAX, SERIAL_ECHOLNPGM)(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]); #endif - #if HAS_U_AXIS && AXIS_CAN_CALIBRATE(U) - #if ENABLED(CALIBRATION_MEASURE_UMIN) - SERIAL_ECHOLNPGM(" " STR_U_MIN ": ", m.backlash[UMINIMUM]); - #endif - #if ENABLED(CALIBRATION_MEASURE_UMAX) - SERIAL_ECHOLNPGM(" " STR_U_MAX ": ", m.backlash[UMAXIMUM]); - #endif + #if AXIS_CAN_CALIBRATE(U) + TERF(CALIBRATION_MEASURE_UMIN, SERIAL_ECHOLNPGM)(" " STR_U_MIN ": ", m.backlash[UMINIMUM]); + TERF(CALIBRATION_MEASURE_UMAX, SERIAL_ECHOLNPGM)(" " STR_U_MAX ": ", m.backlash[UMAXIMUM]); #endif - #if HAS_V_AXIS && AXIS_CAN_CALIBRATE(V) - #if ENABLED(CALIBRATION_MEASURE_VMIN) - SERIAL_ECHOLNPGM(" " STR_V_MIN ": ", m.backlash[VMINIMUM]); - #endif - #if ENABLED(CALIBRATION_MEASURE_VMAX) - SERIAL_ECHOLNPGM(" " STR_V_MAX ": ", m.backlash[VMAXIMUM]); - #endif + #if AXIS_CAN_CALIBRATE(V) + TERF(CALIBRATION_MEASURE_VMIN, SERIAL_ECHOLNPGM)(" " STR_V_MIN ": ", m.backlash[VMINIMUM]); + TERF(CALIBRATION_MEASURE_VMAX, SERIAL_ECHOLNPGM)(" " STR_V_MAX ": ", m.backlash[VMAXIMUM]); #endif - #if HAS_W_AXIS && AXIS_CAN_CALIBRATE(W) - #if ENABLED(CALIBRATION_MEASURE_WMIN) - SERIAL_ECHOLNPGM(" " STR_W_MIN ": ", m.backlash[WMINIMUM]); - #endif - #if ENABLED(CALIBRATION_MEASURE_WMAX) - SERIAL_ECHOLNPGM(" " STR_W_MAX ": ", m.backlash[WMAXIMUM]); - #endif + #if AXIS_CAN_CALIBRATE(W) + TERF(CALIBRATION_MEASURE_WMIN, SERIAL_ECHOLNPGM)(" " STR_W_MIN ": ", m.backlash[WMINIMUM]); + TERF(CALIBRATION_MEASURE_WMAX, SERIAL_ECHOLNPGM)(" " STR_W_MAX ": ", m.backlash[WMAXIMUM]); #endif SERIAL_EOL(); } @@ -575,7 +530,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if HAS_Y_CENTER && AXIS_CAN_CALIBRATE(Y) SERIAL_ECHOLNPGM_P(SP_Y_STR, m.pos_error.y); #endif - #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPGM_P(SP_Z_STR, m.pos_error.z); #endif #if HAS_I_CENTER && AXIS_CAN_CALIBRATE(I) @@ -601,12 +556,8 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { inline void report_measured_nozzle_dimensions(const measurements_t &m) { SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:"); - #if HAS_X_CENTER - SERIAL_ECHOLNPGM_P(SP_X_STR, m.nozzle_outer_dimension.x); - #endif - #if HAS_Y_CENTER - SERIAL_ECHOLNPGM_P(SP_Y_STR, m.nozzle_outer_dimension.y); - #endif + TERF(HAS_X_CENTER, SERIAL_ECHOLNPGM_P)(SP_X_STR, m.nozzle_outer_dimension.x); + TERF(HAS_Y_CENTER, SERIAL_ECHOLNPGM_P)(SP_Y_STR, m.nozzle_outer_dimension.y); SERIAL_EOL(); UNUSED(m); } @@ -616,7 +567,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // This function requires normalize_hotend_offsets() to be called // inline void report_hotend_offsets() { - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) SERIAL_ECHOLNPGM_P(PSTR("T"), e, PSTR(" Hotend Offset X"), hotend_offset[e].x, SP_Y_STR, hotend_offset[e].y, SP_Z_STR, hotend_offset[e].z); } #endif diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index c484d4f1b7..35f7ac3174 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -34,55 +34,60 @@ #include "../../module/probe.h" #include "../../feature/bedlevel/bedlevel.h" #include "../../module/temperature.h" -#include "../../module/probe.h" #include "../../feature/probe_temp_comp.h" #include "../../lcd/marlinui.h" /** - * G76: calibrate probe and/or bed temperature offsets - * Notes: - * - When calibrating probe, bed temperature is held constant. - * Compensation values are deltas to first probe measurement at probe temp. = 30°C. - * - When calibrating bed, probe temperature is held constant. - * Compensation values are deltas to first probe measurement at bed temp. = 60°C. - * - The hotend will not be heated at any time. - * - On my Průša MK3S clone I put a piece of paper between the probe and the hotend - * so the hotend fan would not cool my probe constantly. Alternatively you could just - * make sure the fan is not running while running the calibration process. + * G76: Probe Temperature Calibration * - * Probe calibration: - * - Moves probe to cooldown point. - * - Heats up bed to 100°C. - * - Moves probe to probing point (1mm above heatbed). - * - Waits until probe reaches target temperature (30°C). - * - Does a z-probing (=base value) and increases target temperature by 5°C. - * - Waits until probe reaches increased target temperature. - * - Does a z-probing (delta to base value will be a compensation value) and increases target temperature by 5°C. - * - Repeats last two steps until max. temperature reached or timeout (i.e. probe does not heat up any further). - * - Compensation values of higher temperatures will be extrapolated (using linear regression first). - * While this is not exact by any means it is still better than simply using the last compensation value. + * Calibrate probe and/or bed temperature offsets. * - * Bed calibration: - * - Moves probe to cooldown point. - * - Heats up bed to 60°C. - * - Moves probe to probing point (1mm above heatbed). - * - Waits until probe reaches target temperature (30°C). - * - Does a z-probing (=base value) and increases bed temperature by 5°C. - * - Moves probe to cooldown point. - * - Waits until probe is below 30°C and bed has reached target temperature. - * - Moves probe to probing point and waits until it reaches target temperature (30°C). - * - Does a z-probing (delta to base value will be a compensation value) and increases bed temperature by 5°C. - * - Repeats last four points until max. bed temperature reached (110°C) or timeout. - * - Compensation values of higher temperatures will be extrapolated (using linear regression first). - * While this is not exact by any means it is still better than simply using the last compensation value. + * Probe calibration: + * - Moves probe to cooldown point. + * - Heats up bed to 100°C. + * - Moves probe to probing point (1mm above heatbed). + * - Waits until probe reaches target temperature (30°C). + * - Does a z-probing (=base value) and increases target temperature by 5°C. + * - Waits until probe reaches increased target temperature. + * - Does a z-probing (delta to base value will be a compensation value) and increases target temperature by 5°C. + * - Repeats last two steps until max. temperature reached or timeout (i.e. probe does not heat up any further). + * - Compensation values of higher temperatures will be extrapolated (using linear regression first). + * While this is not exact by any means it is still better than simply using the last compensation value. * - * G76 [B | P] - * - no flag - Both calibration procedures will be run. - * - `B` - Run bed temperature calibration. - * - `P` - Run probe temperature calibration. + * Bed calibration: + * - Moves probe to cooldown point. + * - Heats up bed to 60°C. + * - Moves probe to probing point (1mm above heatbed). + * - Waits until probe reaches target temperature (30°C). + * - Does a z-probing (=base value) and increases bed temperature by 5°C. + * - Moves probe to cooldown point. + * - Waits until probe is below 30°C and bed has reached target temperature. + * - Moves probe to probing point and waits until it reaches target temperature (30°C). + * - Does a z-probing (delta to base value will be a compensation value) and increases bed temperature by 5°C. + * - Repeats last four points until max. bed temperature reached (110°C) or timeout. + * - Compensation values of higher temperatures will be extrapolated (using linear regression first). + * While this is not exact by any means it is still better than simply using the last compensation value. + * + * Usage: + * G76 [ B | P ] + * + * Parameters: + * None Run Both calibration procedures + * B Calibrate bed only + * P Calibrate probe only + * + * NOTES: + * - When calibrating probe, bed temperature is held constant. + * Compensation values are deltas to first probe measurement at probe temp. = 30°C. + * - When calibrating bed, probe temperature is held constant. + * Compensation values are deltas to first probe measurement at bed temp. = 60°C. + * - The hotend will not be heated at any time. + * - On my Průša MK3S clone I put a piece of paper between the probe and the hotend + * so the hotend fan would not cool my probe constantly. Alternatively you could just + * make sure the fan is not running while running the calibration process. */ -#if BOTH(PTC_PROBE, PTC_BED) +#if ALL(PTC_PROBE, PTC_BED) static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); } static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); } @@ -91,7 +96,7 @@ void GcodeSuite::G76() { auto report_temps = [](millis_t &ntr, millis_t timeout=0) { - idle_no_sleep(); + marlin.idle_no_sleep(); const millis_t ms = millis(); if (ELAPSED(ms, ntr)) { ntr = ms + 1000; @@ -108,14 +113,13 @@ }; auto g76_probe = [](const TempSensorID sid, celsius_t &targ, const xy_pos_t &nozpos) { - do_z_clearance(5.0); // Raise nozzle before probing ptc.set_enabled(false); const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false ptc.set_enabled(true); if (isnan(measured_z)) SERIAL_ECHOLNPGM("!Received NAN. Aborting."); else { - SERIAL_ECHOLNPAIR_F("Measured: ", measured_z); + SERIAL_ECHOLNPGM("Measured: ", p_float_t(measured_z, 2)); if (targ == ProbeTempComp::cali_info[sid].start_temp) ptc.prepare_new_calibration(measured_z); else @@ -258,7 +262,7 @@ say_waiting_for_probe_heating(); SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe); - const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL); + const millis_t probe_timeout_ms = millis() + MIN_TO_MS(15); while (thermalManager.degProbe() < target_probe) { if (report_temps(next_temp_report, probe_timeout_ms)) { SERIAL_ECHOLNPGM("!Probe heating timed out."); @@ -293,26 +297,30 @@ #endif // PTC_PROBE && PTC_BED /** - * M871: Report / reset temperature compensation offsets. - * Note: This does not affect values in EEPROM until M500. + * M871: Probe Temperature Config * + * Report / reset temperature compensation offsets. + * NOTE: This does not affect values in EEPROM until M500. + * + * Usage: * M871 [ R | B | P | E ] * - * No Parameters - Print current offset values. + * Parameters: + * None Print current offset values * - * Select only one of these flags: - * R - Reset all offsets to zero (i.e., disable compensation). - * B - Manually set offset for bed - * P - Manually set offset for probe - * E - Manually set offset for extruder + * Select only one of these flags: + * R Reset all offsets to zero (i.e., disable compensation) + * B Manually set offset for bed + * P Manually set offset for probe + * E Manually set offset for extruder * - * With B, P, or E: - * I[index] - Index in the array - * V[value] - Adjustment in µm + * With B, P, or E: + * I Index in the array + * V Adjustment in µm */ void GcodeSuite::M871() { - if (parser.seen('R')) { + if (parser.seen_test('R')) { // Reset z-probe offsets to factory defaults ptc.clear_all_offsets(); SERIAL_ECHOLNPGM("Offsets reset to default."); diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index 338392b597..822ce969ec 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -28,39 +28,37 @@ #include "../queue.h" #include "../../libs/hex_print.h" -#include "../../MarlinCore.h" // for idle() - /** - * M100 Free Memory Watcher + * M100: Free Memory Watcher * * This code watches the free memory block between the bottom of the heap and the top of the stack. * This memory block is initialized and watched via the M100 command. * - * M100 I Initializes the free memory block and prints vitals statistics about the area + * Parameters: + * I Initializes the free memory block and prints vitals statistics about the area * - * M100 F Identifies how much of the free memory block remains free and unused. It also - * detects and reports any corruption within the free memory block that may have - * happened due to errant firmware. + * F Identifies how much of the free memory block remains free and unused. It also + * detects and reports any corruption within the free memory block that may have + * happened due to errant firmware. * - * M100 D Does a hex display of the free memory block along with a flag for any errant - * data that does not match the expected value. + * D Does a hex display of the free memory block along with a flag for any errant + * data that does not match the expected value. * - * M100 C x Corrupts x locations within the free memory block. This is useful to check the - * correctness of the M100 F and M100 D commands. + * C x Corrupts x locations within the free memory block. This is useful to check the + * correctness of the M100 F and M100 D commands. * * Also, there are two support functions that can be called from a developer's C code. - * - * uint16_t check_for_free_memory_corruption(PGM_P const free_memory_start); - * void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size); + * uint16_t check_for_free_memory_corruption(PGM_P const free_memory_start); + * void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size); * * Initial version by Roxy-3D */ -#define M100_FREE_MEMORY_DUMPER // Enable for the `M100 D` Dump sub-command -#define M100_FREE_MEMORY_CORRUPTOR // Enable for the `M100 C` Corrupt sub-command +#define M100_FREE_MEMORY_DUMPER // Enable for the 'M100 D' Dump sub-command +#define M100_FREE_MEMORY_CORRUPTOR // Enable for the 'M100 C' Corrupt sub-command #define TEST_BYTE ((char) 0xE5) -#if EITHER(__AVR__, IS_32BIT_TEENSY) +#if ANY(__AVR__, IS_32BIT_TEENSY) && !IS_TEENSY_40_41 extern char __bss_end; char *end_bss = &__bss_end, @@ -163,14 +161,14 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { while (start_free_memory < end_free_memory) { print_hex_address(start_free_memory); // Print the address SERIAL_CHAR(':'); - LOOP_L_N(i, 16) { // and 16 data bytes + for (uint8_t i = 0; i < 16; ++i) { // and 16 data bytes if (i == 8) SERIAL_CHAR('-'); print_hex_byte(start_free_memory[i]); SERIAL_CHAR(' '); } serial_delay(25); SERIAL_CHAR('|'); // Point out non test bytes - LOOP_L_N(i, 16) { + for (uint8_t i = 0; i < 16; ++i) { char ccc = (char)start_free_memory[i]; // cast to char before automatically casting to char on assignment, in case the compiler is broken ccc = (ccc == TEST_BYTE) ? ' ' : '?'; SERIAL_CHAR(ccc); @@ -178,12 +176,12 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { SERIAL_EOL(); start_free_memory += 16; serial_delay(25); - idle(); + marlin.idle(); } } void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size) { - SERIAL_ECHOLNF(title); + SERIAL_ECHOLN(title); // // Round the start and end locations to produce full lines of output // @@ -197,7 +195,7 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { #endif // M100_FREE_MEMORY_DUMPER inline int check_for_free_memory_corruption(FSTR_P const title) { - SERIAL_ECHOF(title); + SERIAL_ECHO(title); char *start_free_memory = free_memory_start, *end_free_memory = free_memory_end; int n = end_free_memory - start_free_memory; @@ -209,12 +207,12 @@ inline int check_for_free_memory_corruption(FSTR_P const title) { if (end_free_memory < start_free_memory) { SERIAL_ECHOPGM(" end_free_memory < Heap "); //SET_INPUT_PULLUP(63); // if the developer has a switch wired up to their controller board - //safe_delay(5); // this code can be enabled to pause the display as soon as the - //while ( READ(63)) // malfunction is detected. It is currently defaulting to a switch - // idle(); // being on pin-63 which is unassigend and available on most controller - //safe_delay(20); // boards. + //safe_delay(5); // this code can be enabled to pause the display as soon as the + //while ( READ(63)) // malfunction is detected. It is currently defaulting to a switch + // marlin.idle(); // being on pin-63 which is unassigend and available on most controller + //safe_delay(20); // boards. //while ( !READ(63)) - // idle(); + // marlin.idle(); serial_delay(20); #if ENABLED(M100_FREE_MEMORY_DUMPER) M100_dump_routine(F(" Memory corruption detected with end_free_memory bool { + #define _CAN_CASE(N) case N##_AXIS: return bool(AXIS_CAN_CALIBRATE(N)); switch (a) { - default: return false; MAIN_AXIS_MAP(_CAN_CASE) + default: break; } + return false; }; LOOP_NUM_AXES(a) { @@ -93,7 +94,7 @@ void GcodeSuite::M425() { #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) SERIAL_ECHOPGM(" Average measured backlash (mm):"); if (backlash.has_any_measurement()) { - LOOP_NUM_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) { + LOOP_NUM_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement((AxisEnum)a)) { SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_STR[a]), backlash.get_measurement((AxisEnum)a)); } } @@ -105,24 +106,29 @@ void GcodeSuite::M425() { } void GcodeSuite::M425_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_BACKLASH_COMPENSATION)); - SERIAL_ECHOLNPGM_P( + SERIAL_ECHOPGM_P( PSTR(" M425 F"), backlash.get_correction() #ifdef BACKLASH_SMOOTHING_MM , PSTR(" S"), LINEAR_UNIT(backlash.get_smoothing_mm()) #endif - , LIST_N(DOUBLE(NUM_AXES), - SP_X_STR, LINEAR_UNIT(backlash.get_distance_mm(X_AXIS)), - SP_Y_STR, LINEAR_UNIT(backlash.get_distance_mm(Y_AXIS)), - SP_Z_STR, LINEAR_UNIT(backlash.get_distance_mm(Z_AXIS)), - SP_I_STR, I_AXIS_UNIT(backlash.get_distance_mm(I_AXIS)), - SP_J_STR, J_AXIS_UNIT(backlash.get_distance_mm(J_AXIS)), - SP_K_STR, K_AXIS_UNIT(backlash.get_distance_mm(K_AXIS)), - SP_U_STR, U_AXIS_UNIT(backlash.get_distance_mm(U_AXIS)), - SP_V_STR, V_AXIS_UNIT(backlash.get_distance_mm(V_AXIS)), - SP_W_STR, W_AXIS_UNIT(backlash.get_distance_mm(W_AXIS)) - ) ); + #if NUM_AXES + SERIAL_ECHOPGM_P(NUM_AXIS_PAIRED_LIST( + SP_X_STR, LINEAR_UNIT(backlash.get_distance_mm(X_AXIS)), + SP_Y_STR, LINEAR_UNIT(backlash.get_distance_mm(Y_AXIS)), + SP_Z_STR, LINEAR_UNIT(backlash.get_distance_mm(Z_AXIS)), + SP_I_STR, I_AXIS_UNIT(backlash.get_distance_mm(I_AXIS)), + SP_J_STR, J_AXIS_UNIT(backlash.get_distance_mm(J_AXIS)), + SP_K_STR, K_AXIS_UNIT(backlash.get_distance_mm(K_AXIS)), + SP_U_STR, U_AXIS_UNIT(backlash.get_distance_mm(U_AXIS)), + SP_V_STR, V_AXIS_UNIT(backlash.get_distance_mm(V_AXIS)), + SP_W_STR, W_AXIS_UNIT(backlash.get_distance_mm(W_AXIS)) + )); + #endif + SERIAL_EOL(); } #endif // BACKLASH_GCODE diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 8b6ea0bf1f..0c4355f5b1 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -62,16 +62,13 @@ void GcodeSuite::M48() { const int8_t verbose_level = parser.byteval('V', 1); if (!WITHIN(verbose_level, 0, 4)) { - SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("(V)erbose level implausible (0-4).")); return; } - if (verbose_level > 0) - SERIAL_ECHOLNPGM("M48 Z-Probe Repeatability Test"); - const int8_t n_samples = parser.byteval('P', 10); if (!WITHIN(n_samples, 4, 50)) { - SERIAL_ECHOLNPGM("?Sample size not plausible (4-50)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Sample size not plausible (4-50).")); return; } @@ -84,8 +81,8 @@ void GcodeSuite::M48() { }; if (!probe.can_reach(test_position)) { - ui.set_status(GET_TEXT_F(MSG_M48_OUT_OF_BOUNDS), 99); - SERIAL_ECHOLNPGM("? (X,Y) out of bounds."); + LCD_MESSAGE_MAX(MSG_M48_OUT_OF_BOUNDS); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG(" (X,Y) out of bounds.")); return; } @@ -93,7 +90,7 @@ void GcodeSuite::M48() { bool seen_L = parser.seen('L'); uint8_t n_legs = seen_L ? parser.value_byte() : 0; if (n_legs > 15) { - SERIAL_ECHOLNPGM("?Legs of movement implausible (0-15)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Legs of movement implausible (0-15).")); return; } if (n_legs == 1) n_legs = 2; @@ -102,6 +99,9 @@ void GcodeSuite::M48() { const bool schizoid_flag = parser.boolval('S'); if (schizoid_flag && !seen_L) n_legs = 7; + if (verbose_level > 0) + SERIAL_ECHOLNPGM("M48 Z-Probe Repeatability Test"); + if (verbose_level > 2) SERIAL_ECHOLNPGM("Positioning the probe..."); @@ -112,7 +112,7 @@ void GcodeSuite::M48() { set_bed_leveling_enabled(false); #endif - TERN_(HAS_PTC, ptc.set_enabled(!parser.seen('C') || parser.value_bool())); + TERN_(HAS_PTC, ptc.set_enabled(parser.boolval('C', true))); // Work with reasonable feedrates remember_feedrate_scaling_off(); @@ -124,17 +124,15 @@ void GcodeSuite::M48() { max = -99999.9, // Largest value sampled so far sample_set[n_samples]; // Storage for sampled values - auto dev_report = [](const bool verbose, const_float_t mean, const_float_t sigma, const_float_t min, const_float_t max, const bool final=false) { + auto dev_report = [](const bool verbose, const float mean, const float sigma, const float min, const float max, const bool final=false) { if (verbose) { - SERIAL_ECHOPAIR_F("Mean: ", mean, 6); - if (!final) SERIAL_ECHOPAIR_F(" Sigma: ", sigma, 6); - SERIAL_ECHOPAIR_F(" Min: ", min, 3); - SERIAL_ECHOPAIR_F(" Max: ", max, 3); - SERIAL_ECHOPAIR_F(" Range: ", max-min, 3); + SERIAL_ECHOPGM("Mean: ", p_float_t(mean, 6)); + if (!final) SERIAL_ECHOPGM(" Sigma: ", p_float_t(sigma, 6)); + SERIAL_ECHOPGM(" Min: ", p_float_t(min, 3), " Max: ", p_float_t(max, 3), " Range: ", p_float_t(max-min, 3)); if (final) SERIAL_EOL(); } if (final) { - SERIAL_ECHOLNPAIR_F("Standard Deviation: ", sigma, 6); + SERIAL_ECHOLNPGM("Standard Deviation: ", p_float_t(sigma, 6)); SERIAL_EOL(); } }; @@ -148,7 +146,7 @@ void GcodeSuite::M48() { float sample_sum = 0.0; - LOOP_L_N(n, n_samples) { + for (uint8_t n = 0; n < n_samples; ++n) { #if HAS_STATUS_MESSAGE // Display M48 progress in the status bar ui.status_printf(0, F(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples)); @@ -162,8 +160,8 @@ void GcodeSuite::M48() { float angle = random(0, 360); const float radius = random( #if ENABLED(DELTA) - int(0.1250000000 * (DELTA_PRINTABLE_RADIUS)), - int(0.3333333333 * (DELTA_PRINTABLE_RADIUS)) + int(0.1250000000 * (PRINTABLE_RADIUS)), + int(0.3333333333 * (PRINTABLE_RADIUS)) #else int(5), int(0.125 * _MIN(X_BED_SIZE, Y_BED_SIZE)) #endif @@ -175,7 +173,7 @@ void GcodeSuite::M48() { } // Move from leg to leg in rapid succession - LOOP_L_N(l, n_legs - 1) { + for (uint8_t l = 0; l < n_legs - 1; ++l) { // Move some distance around the perimeter float delta_angle; @@ -207,7 +205,7 @@ void GcodeSuite::M48() { while (!probe.can_reach(next_pos)) { next_pos *= 0.8f; if (verbose_level > 3) - SERIAL_ECHOLNPGM_P(PSTR("Moving inward: X"), next_pos.x, SP_Y_STR, next_pos.y); + SERIAL_ECHOLN(F("Moving inward: X"), next_pos.x, FPSTR(SP_Y_STR), next_pos.y); } #elif HAS_ENDSTOPS // For a rectangular bed just keep the probe in bounds @@ -216,14 +214,14 @@ void GcodeSuite::M48() { #endif if (verbose_level > 3) - SERIAL_ECHOLNPGM_P(PSTR("Going to: X"), next_pos.x, SP_Y_STR, next_pos.y); + SERIAL_ECHOLN(F("Going to: X"), next_pos.x, FPSTR(SP_Y_STR), next_pos.y); do_blocking_move_to_xy(next_pos); } // n_legs loop } // n_legs // Probe a single point - const float pz = probe.probe_at_point(test_position, raise_after, 0); + const float pz = probe.probe_at_point(test_position, raise_after); // Break the loop if the probe fails probing_good = !isnan(pz); @@ -243,14 +241,11 @@ void GcodeSuite::M48() { // Calculate the standard deviation so far. // The value after the last sample will be the final output. float dev_sum = 0.0; - LOOP_LE_N(j, n) dev_sum += sq(sample_set[j] - mean); + for (uint8_t j = 0; j <= n; ++j) dev_sum += sq(sample_set[j] - mean); sigma = SQRT(dev_sum / (n + 1)); if (verbose_level > 1) { - SERIAL_ECHO(n + 1); - SERIAL_ECHOPGM(" of ", n_samples); - SERIAL_ECHOPAIR_F(": z: ", pz, 3); - SERIAL_CHAR(' '); + SERIAL_ECHO(n + 1, F(" of "), n_samples, F(": z: "), p_float_t(pz, 3), C(' ')); dev_report(verbose_level > 2, mean, sigma, min, max); SERIAL_EOL(); } @@ -266,8 +261,19 @@ void GcodeSuite::M48() { #if HAS_STATUS_MESSAGE // Display M48 results in the status bar - char sigma_str[8]; - ui.status_printf(0, F(S_FMT ": %s"), GET_TEXT(MSG_M48_DEVIATION), dtostrf(sigma, 2, 6, sigma_str)); + if (MAX_MESSAGE_SIZE <= 20) { + // 12345678901234567890 + // Deviation: 0.123456 + ui.set_status_and_level(TS(GET_TEXT_F(MSG_M48_DEVIATION), F(": "), w_float_t(sigma, 2, 6))); + } else if (MAX_MESSAGE_SIZE <= 30) { + // 123456789012345678901234567890 + // Dev:0.12345, Max delta:0.12345 + ui.set_status_and_level(TS(GET_TEXT_F(MSG_M48_DEV), ':', w_float_t(sigma, 2, 5), F(", "), GET_TEXT(MSG_M48_MAX_DELTA), ':', w_float_t(_MAX(mean - min, max - mean), 2, 5))); + } else { + // 1234567890123456789012345678901234567890 + // Deviation: 1.23456, Max delta: 1.23456 + ui.set_status_and_level(TS(GET_TEXT_F(MSG_M48_DEVIATION), F(": "), w_float_t(sigma, 2, 6), F(", "), GET_TEXT(MSG_M48_MAX_DELTA), F(": "), w_float_t(_MAX(mean - min, max - mean), 2, 6))); + } #endif } diff --git a/Marlin/src/gcode/calibrate/M665.cpp b/Marlin/src/gcode/calibrate/M665.cpp index 7dc657a61b..5409ff4232 100644 --- a/Marlin/src/gcode/calibrate/M665.cpp +++ b/Marlin/src/gcode/calibrate/M665.cpp @@ -62,6 +62,8 @@ } void GcodeSuite::M665_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_DELTA_SETTINGS)); SERIAL_ECHOLNPGM_P( PSTR(" M665 L"), LINEAR_UNIT(delta_diagonal_rod) @@ -132,6 +134,8 @@ } void GcodeSuite::M665_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_SCARA_SETTINGS " (" STR_S_SEG_PER_SEC TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")")); SERIAL_ECHOLNPGM_P( PSTR(" M665 S"), segments_per_second @@ -167,11 +171,11 @@ if (parser.seenval('T')) draw_area_max.y = parser.value_linear_units(); if (parser.seenval('B')) draw_area_min.y = parser.value_linear_units(); if (parser.seenval('H')) polargraph_max_belt_len = parser.value_linear_units(); - draw_area_size.x = draw_area_max.x - draw_area_min.x; - draw_area_size.y = draw_area_max.y - draw_area_min.y; } void GcodeSuite::M665_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_POLARGRAPH_SETTINGS)); SERIAL_ECHOLNPGM_P( PSTR(" M665 S"), LINEAR_UNIT(segments_per_second), @@ -183,6 +187,26 @@ ); } -#endif +#elif ENABLED(POLAR) + + #include "../../module/polar.h" + + /** + * M665: Set POLAR settings + * Parameters: + * S[segments] - Segments-per-second + */ + void GcodeSuite::M665() { + if (!parser.seen_any()) return M665_report(); + if (parser.seenval('S')) segments_per_second = parser.value_float(); + } + + void GcodeSuite::M665_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_POLAR_SETTINGS)); + SERIAL_ECHOLNPGM_P(PSTR(" M665 S"), segments_per_second); + } + +#endif // POLAR #endif // IS_KINEMATIC diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 90fad1811c..2584782cf3 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS +#if ANY(DELTA, HAS_EXTRA_ENDSTOPS) #include "../gcode.h" @@ -39,7 +39,15 @@ #if ENABLED(DELTA) /** - * M666: Set delta endstop adjustment + * M666: Set Delta endstop adjustments + * + * Adjust the endstop offsets on a Delta printer. + * + * Parameters: + * None Report current offsets + * X Adjustment for the X actuator endstop + * Y Adjustment for the Y actuator endstop + * Z Adjustment for the Z actuator endstop */ void GcodeSuite::M666() { DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING)); @@ -52,15 +60,17 @@ is_err = true; else { delta_endstop_adj[i] = v; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", v); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("delta_endstop_adj[", C(AXIS_CHAR(i)), "] = ", v); } } } - if (is_err) SERIAL_ECHOLNPGM("?M666 offsets must be <= 0"); + if (is_err) SERIAL_ECHOLNPGM(GCODE_ERR_MSG("M666 offsets must be <= 0")); if (!is_set) M666_report(); } void GcodeSuite::M666_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_ENDSTOP_ADJUSTMENT)); SERIAL_ECHOLNPGM_P( PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) @@ -72,14 +82,22 @@ #else /** - * M666: Set Dual Endstops offsets for X, Y, and/or Z. - * With no parameters report current offsets. + * M666: Set Dual Endstop Offsets * - * For Triple / Quad Z Endstops: - * Set Z2 Only: M666 S2 Z - * Set Z3 Only: M666 S3 Z - * Set Z4 Only: M666 S4 Z - * Set All: M666 Z + * Adjust the offsets for dual (or multiple) endstops. + * + * Parameters: + * None Report current offsets + * X Offset for the X axis endstops + * Y Offset for the Y axis endstops + * Z Offset for the Z axis endstops + * + * Example: + * For Triple / Quad Z Endstops: + * M666 S2 Z ; Set Z2 Only + * M666 S3 Z ; Set Z3 Only + * M666 S4 Z ; Set Z4 Only + * M666 Z ; Set All */ void GcodeSuite::M666() { if (!parser.seen_any()) return M666_report(); @@ -105,6 +123,8 @@ } void GcodeSuite::M666_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_ENDSTOP_ADJUSTMENT)); SERIAL_ECHOPGM(" M666"); #if ENABLED(X_DUAL_ENDSTOPS) diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp index 6c661dcd61..7cd9aaf718 100644 --- a/Marlin/src/gcode/calibrate/M852.cpp +++ b/Marlin/src/gcode/calibrate/M852.cpp @@ -28,12 +28,16 @@ #include "../../module/planner.h" /** - * M852: Get or set the machine skew factors. Reports current values with no arguments. + * M852: Bed Skew Compensation * - * S[xy_factor] - Alias for 'I' - * I[xy_factor] - New XY skew factor - * J[xz_factor] - New XZ skew factor - * K[yz_factor] - New YZ skew factor + * Get or set the machine skew factors; correct for misalignment + * + * Parameters: + * None Report current values + * S Alias for 'I' + * I New XY skew factor + * J New XZ skew factor + * K New YZ skew factor */ void GcodeSuite::M852() { if (!parser.seen("SIJK")) return M852_report(); @@ -92,12 +96,12 @@ void GcodeSuite::M852() { } void GcodeSuite::M852_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_SKEW_FACTOR)); - SERIAL_ECHOPAIR_F(" M852 I", planner.skew_factor.xy, 6); + SERIAL_ECHOPGM(" M852 I", p_float_t(planner.skew_factor.xy, 6)); #if ENABLED(SKEW_CORRECTION_FOR_Z) - SERIAL_ECHOPAIR_F(" J", planner.skew_factor.xz, 6); - SERIAL_ECHOPAIR_F(" K", planner.skew_factor.yz, 6); - SERIAL_ECHOLNPGM(" ; XY, XZ, YZ"); + SERIAL_ECHOLNPGM(" J", p_float_t(planner.skew_factor.xz, 6), " K", p_float_t(planner.skew_factor.yz, 6), " ; XY, XZ, YZ"); #else SERIAL_ECHOLNPGM(" ; XY"); #endif diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 87c1f2ce30..53d0b4b4a8 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -24,7 +24,7 @@ #include "../../MarlinCore.h" #include "../../module/planner.h" -#if DISABLED(NO_VOLUMETRICS) +#if HAS_VOLUMETRIC_EXTRUSION /** * M200: Set filament diameter and set E axis units to cubic units @@ -64,10 +64,10 @@ if (parser.seenval('L')) { // Set volumetric limit (in mm^3/sec) const float lval = parser.value_float(); - if (WITHIN(lval, 0, 20)) + if (WITHIN(lval, 0, VOLUMETRIC_EXTRUDER_LIMIT_MAX)) planner.set_volumetric_extruder_limit(target_extruder, lval); else - SERIAL_ECHOLNPGM("?L value out of range (0-20)."); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("L value out of range (0-" STRINGIFY(VOLUMETRIC_EXTRUDER_LIMIT_MAX) ").")); } #endif @@ -75,11 +75,13 @@ } void GcodeSuite::M200_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + if (!forReplay) { - report_heading(forReplay, F(STR_FILAMENT_SETTINGS), false); + report_heading(false, F(STR_FILAMENT_SETTINGS), false); if (!parser.volumetric_enabled) SERIAL_ECHOPGM(" (Disabled):"); SERIAL_EOL(); - report_echo_start(forReplay); + report_echo_start(false); } #if EXTRUDERS == 1 @@ -105,7 +107,7 @@ #endif } -#endif // !NO_VOLUMETRICS +#endif // HAS_VOLUMETRIC_EXTRUSION /** * M201: Set max acceleration in units/s^2 for print moves. @@ -122,8 +124,13 @@ * S : Speed factor percentage. */ void GcodeSuite::M201() { - if (!parser.seen("T" STR_AXES_LOGICAL TERN_(XY_FREQUENCY_LIMIT, "FS"))) + if (!parser.seen("T" STR_AXES_LOGICAL + #ifdef XY_FREQUENCY_LIMIT + "FS" + #endif + )) { return M201_report(); + } const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; @@ -142,9 +149,15 @@ void GcodeSuite::M201() { } void GcodeSuite::M201_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_MAX_ACCELERATION)); - SERIAL_ECHOLNPGM_P( - LIST_N(DOUBLE(NUM_AXES), + + bool eol = false; + + #if NUM_AXES + eol = true; + SERIAL_ECHOPGM_P(NUM_AXIS_PAIRED_LIST( PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]), @@ -154,13 +167,24 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) { SP_U_STR, U_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[U_AXIS]), SP_V_STR, V_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[V_AXIS]), SP_W_STR, W_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[W_AXIS]) - ) - #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) - , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]) - #endif - ); + )); + #endif + + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + eol = true; + SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])); + #endif + + #ifdef XY_FREQUENCY_LIMIT + eol = true; + SERIAL_ECHOPGM_P(PSTR(" F"), planner.xy_freq_limit_hz); + SERIAL_ECHOPGM_P(PSTR(" S"), (planner.xy_freq_min_speed_factor * 100)); + #endif + + if (eol) SERIAL_EOL(); + #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { + for (uint8_t i = 0; i < E_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M201 T"), i @@ -190,9 +214,15 @@ void GcodeSuite::M203() { } void GcodeSuite::M203_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_MAX_FEEDRATES)); - SERIAL_ECHOLNPGM_P( - LIST_N(DOUBLE(NUM_AXES), + + bool eol = false; + + #if NUM_AXES + eol = true; + SERIAL_ECHOPGM_P(NUM_AXIS_PAIRED_LIST( PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]), @@ -202,14 +232,19 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) { SP_U_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[U_AXIS]), SP_V_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[V_AXIS]), SP_W_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[W_AXIS]) - ) - #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) - , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]) - #endif - ); + )); + #endif + + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + eol = true; + SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])); + #endif + + if (eol) SERIAL_EOL(); + #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { - if (!forReplay) SERIAL_ECHO_START(); + for (uint8_t i = 0; i < E_STEPPERS; ++i) { + report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M203 T"), i , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]) @@ -221,9 +256,9 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) { /** * M204: Set Accelerations in units/sec^2 (M204 P1200 R3000 T3000) * - * P = Printing moves - * R = Retract only (no X, Y, Z) moves - * T = Travel (non printing) moves + * P Printing moves + * R Retract only (no X, Y, Z) moves + * T Travel (non printing) moves */ void GcodeSuite::M204() { if (!parser.seen("PRST")) @@ -239,6 +274,8 @@ void GcodeSuite::M204() { } void GcodeSuite::M204_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_ACCELERATION_P_R_T)); SERIAL_ECHOLNPGM_P( PSTR(" M204 P"), LINEAR_UNIT(planner.settings.acceleration) @@ -247,41 +284,51 @@ void GcodeSuite::M204_report(const bool forReplay/*=true*/) { ); } +#if AXIS_COLLISION('B') + #define M205_MIN_SEG_TIME_PARAM 'D' + #define M205_MIN_SEG_TIME_STR "D" + #warning "Use 'M205 D' for Minimum Segment Time." +#else + #define M205_MIN_SEG_TIME_PARAM 'B' + #define M205_MIN_SEG_TIME_STR "B" +#endif + /** * M205: Set Advanced Settings * - * B = Min Segment Time (µs) - * S = Min Feed Rate (units/s) - * T = Min Travel Feed Rate (units/s) - * X = Max X Jerk (units/sec^2) - * Y = Max Y Jerk (units/sec^2) - * Z = Max Z Jerk (units/sec^2) - * E = Max E Jerk (units/sec^2) - * J = Junction Deviation (mm) (If not using CLASSIC_JERK) + * B<µs> : Min Segment Time + * S : Min Feed Rate + * T : Min Travel Feed Rate + * + * With CLASSIC_JERK: + * X : Max X Jerk + * Y : Max Y Jerk + * Z : Max Z Jerk + * ... : etc + * E : Max E Jerk + * + * Without CLASSIC_JERK: + * J(mm) : Junction Deviation */ void GcodeSuite::M205() { - if (!parser.seen("BST" TERN_(HAS_JUNCTION_DEVIATION, "J") TERN_(HAS_CLASSIC_JERK, "XYZE"))) - return M205_report(); + if (!parser.seen_any()) return M205_report(); //planner.synchronize(); - if (parser.seenval('B')) planner.settings.min_segment_time_us = parser.value_ulong(); + if (parser.seenval(M205_MIN_SEG_TIME_PARAM)) planner.settings.min_segment_time_us = parser.value_ulong(); if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); #if HAS_JUNCTION_DEVIATION - #if HAS_CLASSIC_JERK && AXIS_COLLISION('J') - #error "Can't set_max_jerk for 'J' axis because 'J' is used for Junction Deviation." - #endif if (parser.seenval('J')) { const float junc_dev = parser.value_linear_units(); if (WITHIN(junc_dev, 0.01f, 0.3f)) { planner.junction_deviation_mm = junc_dev; - TERN_(LIN_ADVANCE, planner.recalculate_max_e_jerk()); + TERN_(HAS_LINEAR_E_JERK, planner.recalculate_max_e_jerk()); } else SERIAL_ERROR_MSG("?J out of range (0.01 to 0.3)"); } #endif - #if HAS_CLASSIC_JERK + #if ENABLED(CLASSIC_JERK) bool seenZ = false; LOGICAL_AXIS_CODE( if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()), @@ -299,14 +346,16 @@ void GcodeSuite::M205() { if (seenZ && planner.max_jerk.z <= 0.1f) SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); #endif - #endif // HAS_CLASSIC_JERK + #endif // CLASSIC_JERK } void GcodeSuite::M205_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F( - "Advanced (B S T" + "Advanced (" M205_MIN_SEG_TIME_STR " S T" TERN_(HAS_JUNCTION_DEVIATION, " J") - #if HAS_CLASSIC_JERK + #if ENABLED(CLASSIC_JERK) NUM_AXIS_GANG( " X", " Y", " Z", " " STR_I "", " " STR_J "", " " STR_K "", @@ -317,14 +366,14 @@ void GcodeSuite::M205_report(const bool forReplay/*=true*/) { ")" )); SERIAL_ECHOLNPGM_P( - PSTR(" M205 B"), LINEAR_UNIT(planner.settings.min_segment_time_us) + PSTR(" M205 " M205_MIN_SEG_TIME_STR), LINEAR_UNIT(planner.settings.min_segment_time_us) , PSTR(" S"), LINEAR_UNIT(planner.settings.min_feedrate_mm_s) , SP_T_STR, LINEAR_UNIT(planner.settings.min_travel_feedrate_mm_s) #if HAS_JUNCTION_DEVIATION , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm) #endif - #if HAS_CLASSIC_JERK - , LIST_N(DOUBLE(NUM_AXES), + #if ENABLED(CLASSIC_JERK) && NUM_AXES + , NUM_AXIS_PAIRED_LIST( SP_X_STR, LINEAR_UNIT(planner.max_jerk.x), SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y), SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z), diff --git a/Marlin/src/gcode/config/M210.cpp b/Marlin/src/gcode/config/M210.cpp new file mode 100644 index 0000000000..41dbd73db4 --- /dev/null +++ b/Marlin/src/gcode/config/M210.cpp @@ -0,0 +1,82 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(EDITABLE_HOMING_FEEDRATE) + +#include "../gcode.h" +#include "../../module/motion.h" + +/** + * M210 - Set homing feedrate for one or more axes + * in current units (in/mm) per minute + * + * X[feedrate] Set X axis homing feedrate + * Y[feedrate] Set Y axis homing feedrate + * Z[feedrate] Set Z axis homing feedrate + * A[feedrate] Set I axis homing feedrate (configured axis name applies) + * B[feedrate] Set J axis homing feedrate (configured axis name applies) + * C[feedrate] Set K axis homing feedrate (configured axis name applies) + * U[feedrate] Set U axis homing feedrate (configured axis name applies) + * V[feedrate] Set V axis homing feedrate (configured axis name applies) + * W[feedrate] Set W axis homing feedrate (configured axis name applies) + * + * With no arguments, report the current offsets. + */ +void GcodeSuite::M210() { + if (!parser.seen_any()) + return M210_report(); + + NUM_AXIS_CODE( + if (parser.floatval(AXIS1_PARAM) > 0) homing_feedrate_mm_m.x = parser.value_axis_units(X_AXIS), + if (parser.floatval(AXIS2_PARAM) > 0) homing_feedrate_mm_m.y = parser.value_axis_units(Y_AXIS), + if (parser.floatval(AXIS3_PARAM) > 0) homing_feedrate_mm_m.z = parser.value_axis_units(Z_AXIS), + if (parser.floatval(AXIS4_PARAM) > 0) homing_feedrate_mm_m.i = parser.value_axis_units(I_AXIS), + if (parser.floatval(AXIS5_PARAM) > 0) homing_feedrate_mm_m.j = parser.value_axis_units(J_AXIS), + if (parser.floatval(AXIS6_PARAM) > 0) homing_feedrate_mm_m.k = parser.value_axis_units(K_AXIS), + if (parser.floatval(AXIS7_PARAM) > 0) homing_feedrate_mm_m.u = parser.value_axis_units(U_AXIS), + if (parser.floatval(AXIS8_PARAM) > 0) homing_feedrate_mm_m.v = parser.value_axis_units(V_AXIS), + if (parser.floatval(AXIS9_PARAM) > 0) homing_feedrate_mm_m.w = parser.value_axis_units(W_AXIS) + ); +} + +void GcodeSuite::M210_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + + report_heading_etc(forReplay, F(STR_HOMING_FEEDRATE)); + + SERIAL_ECHOPGM(" M210"); + SERIAL_ECHOLNPGM_P(NUM_AXIS_PAIRED_LIST( + SP_X_STR, X_AXIS_UNIT(homing_feedrate_mm_m.x), + SP_Y_STR, Y_AXIS_UNIT(homing_feedrate_mm_m.y), + SP_Z_STR, Z_AXIS_UNIT(homing_feedrate_mm_m.z), + SP_I_STR, I_AXIS_UNIT(homing_feedrate_mm_m.i), + SP_J_STR, J_AXIS_UNIT(homing_feedrate_mm_m.j), + SP_K_STR, K_AXIS_UNIT(homing_feedrate_mm_m.k), + SP_U_STR, U_AXIS_UNIT(homing_feedrate_mm_m.u), + SP_V_STR, V_AXIS_UNIT(homing_feedrate_mm_m.v), + SP_W_STR, W_AXIS_UNIT(homing_feedrate_mm_m.w) + )); +} + +#endif // EDITABLE_HOMING_FEEDRATE diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 989e4d0870..df275c2d31 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -25,13 +25,14 @@ #if HAS_MULTI_EXTRUDER #include "../gcode.h" -#include "../../module/tool_change.h" -#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) - #include "../../module/motion.h" +#if HAS_TOOLCHANGE + #include "../../module/tool_change.h" #endif -#include "../../MarlinCore.h" // for SP_X_STR, etc. +#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + #include "../../module/motion.h" // for active_extruder +#endif /** * M217 - Set toolchange parameters @@ -43,13 +44,14 @@ * S[linear] Swap length * B[linear] Extra Swap resume length * E[linear] Extra Prime length (as used by M217 Q) - * P[linear/min] Prime speed + * G[linear] Cutting wipe retract length (<=100mm) * R[linear/min] Retract speed * U[linear/min] UnRetract speed + * P[linear/min] Prime speed * V[linear] 0/1 Enable auto prime first extruder used * W[linear] 0/1 Enable park & Z Raise * X[linear] Park X (Requires TOOLCHANGE_PARK) - * Y[linear] Park Y (Requires TOOLCHANGE_PARK) + * Y[linear] Park Y (Requires TOOLCHANGE_PARK and NUM_AXES >= 2) * I[linear] Park I (Requires TOOLCHANGE_PARK and NUM_AXES >= 4) * J[linear] Park J (Requires TOOLCHANGE_PARK and NUM_AXES >= 5) * K[linear] Park K (Requires TOOLCHANGE_PARK and NUM_AXES >= 6) @@ -79,6 +81,7 @@ void GcodeSuite::M217() { if (parser.seenval('B')) { const float v = parser.value_linear_units(); toolchange_settings.extra_resume = constrain(v, -10, 10); } if (parser.seenval('E')) { const float v = parser.value_linear_units(); toolchange_settings.extra_prime = constrain(v, 0, max_extrude); } if (parser.seenval('P')) { const int16_t v = parser.value_linear_units(); toolchange_settings.prime_speed = constrain(v, 10, 5400); } + if (parser.seenval('G')) { const int16_t v = parser.value_linear_units(); toolchange_settings.wipe_retract = constrain(v, 0, 100); } if (parser.seenval('R')) { const int16_t v = parser.value_linear_units(); toolchange_settings.retract_speed = constrain(v, 10, 5400); } if (parser.seenval('U')) { const int16_t v = parser.value_linear_units(); toolchange_settings.unretract_speed = constrain(v, 10, 5400); } #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN @@ -93,7 +96,9 @@ void GcodeSuite::M217() { #if ENABLED(TOOLCHANGE_PARK) if (parser.seenval('W')) { toolchange_settings.enable_park = parser.value_linear_units(); } - if (parser.seenval('X')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.x = constrain(v, X_MIN_POS, X_MAX_POS); } + #if HAS_X_AXIS + if (parser.seenval('X')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.x = constrain(v, X_MIN_POS, X_MAX_POS); } + #endif #if HAS_Y_AXIS if (parser.seenval('Y')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.y = constrain(v, Y_MIN_POS, Y_MAX_POS); } #endif @@ -117,7 +122,7 @@ void GcodeSuite::M217() { #endif #endif - #if HAS_Z_AXIS + #if HAS_Z_AXIS && HAS_TOOLCHANGE if (parser.seenval('Z')) { toolchange_settings.z_raise = parser.value_linear_units(); } #endif @@ -159,43 +164,51 @@ void GcodeSuite::M217() { } void GcodeSuite::M217_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_TOOL_CHANGING)); SERIAL_ECHOPGM(" M217"); #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - SERIAL_ECHOPGM(" S", LINEAR_UNIT(toolchange_settings.swap_length)); - SERIAL_ECHOPGM_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume), - SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), - SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); - SERIAL_ECHOPGM(" R", LINEAR_UNIT(toolchange_settings.retract_speed), - " U", LINEAR_UNIT(toolchange_settings.unretract_speed), - " F", toolchange_settings.fan_speed, - " D", toolchange_settings.fan_time); + SERIAL_ECHOPGM_P( + PSTR(" S"), LINEAR_UNIT(toolchange_settings.swap_length), + SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume), + SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), + SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed), + PSTR(" G"), LINEAR_UNIT(toolchange_settings.wipe_retract), + PSTR(" R"), LINEAR_UNIT(toolchange_settings.retract_speed), + PSTR(" U"), LINEAR_UNIT(toolchange_settings.unretract_speed), + PSTR(" F"), toolchange_settings.fan_speed, + PSTR(" D"), toolchange_settings.fan_time + ); #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOPGM(" A", migration.automode); - SERIAL_ECHOPGM(" L", LINEAR_UNIT(migration.last)); + SERIAL_ECHOPGM(" A", migration.automode, " L", LINEAR_UNIT(migration.last)); #endif #if ENABLED(TOOLCHANGE_PARK) SERIAL_ECHOPGM(" W", LINEAR_UNIT(toolchange_settings.enable_park)); - SERIAL_ECHOPGM_P( - SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x) - #if HAS_Y_AXIS - , SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y) - #endif - #if SECONDARY_AXES >= 1 - , LIST_N(DOUBLE(SECONDARY_AXES) - , SP_I_STR, I_AXIS_UNIT(toolchange_settings.change_point.i) - , SP_J_STR, J_AXIS_UNIT(toolchange_settings.change_point.j) - , SP_K_STR, K_AXIS_UNIT(toolchange_settings.change_point.k) - , SP_C_STR, U_AXIS_UNIT(toolchange_settings.change_point.u) - , PSTR(" H"), V_AXIS_UNIT(toolchange_settings.change_point.v) - , PSTR(" O"), W_AXIS_UNIT(toolchange_settings.change_point.w) - ) - #endif - ); + #if NUM_AXES + { + SERIAL_ECHOPGM_P( + SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x) + #if HAS_Y_AXIS + , SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y) + #endif + #if SECONDARY_AXES >= 1 + , LIST_N(DOUBLE(SECONDARY_AXES) + , SP_I_STR, I_AXIS_UNIT(toolchange_settings.change_point.i) + , SP_J_STR, J_AXIS_UNIT(toolchange_settings.change_point.j) + , SP_K_STR, K_AXIS_UNIT(toolchange_settings.change_point.k) + , SP_C_STR, U_AXIS_UNIT(toolchange_settings.change_point.u) + , PSTR(" H"), V_AXIS_UNIT(toolchange_settings.change_point.v) + , PSTR(" O"), W_AXIS_UNIT(toolchange_settings.change_point.w) + ) + #endif + ); + } + #endif #endif #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) diff --git a/Marlin/src/gcode/config/M218.cpp b/Marlin/src/gcode/config/M218.cpp index c39447a28d..7d167e502d 100644 --- a/Marlin/src/gcode/config/M218.cpp +++ b/Marlin/src/gcode/config/M218.cpp @@ -46,9 +46,15 @@ void GcodeSuite::M218() { const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; - if (parser.seenval('X')) hotend_offset[target_extruder].x = parser.value_linear_units(); - if (parser.seenval('Y')) hotend_offset[target_extruder].y = parser.value_linear_units(); - if (parser.seenval('Z')) hotend_offset[target_extruder].z = parser.value_linear_units(); + #if HAS_X_AXIS + if (parser.seenval('X')) hotend_offset[target_extruder].x = parser.value_linear_units(); + #endif + #if HAS_Y_AXIS + if (parser.seenval('Y')) hotend_offset[target_extruder].y = parser.value_linear_units(); + #endif + #if HAS_Z_AXIS + if (parser.seenval('Z')) hotend_offset[target_extruder].z = parser.value_linear_units(); + #endif #if ENABLED(DELTA) if (target_extruder == active_extruder) @@ -57,15 +63,17 @@ void GcodeSuite::M218() { } void GcodeSuite::M218_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, F(STR_HOTEND_OFFSETS)); - LOOP_S_L_N(e, 1, HOTENDS) { + TERN_(MARLIN_SMALL_BUILD, return); + + report_heading(forReplay, F(STR_HOTEND_OFFSETS)); + for (uint8_t e = 1; e < HOTENDS; ++e) { report_echo_start(forReplay); - SERIAL_ECHOPGM_P( + SERIAL_ECHOLNPGM_P( PSTR(" M218 T"), e, SP_X_STR, LINEAR_UNIT(hotend_offset[e].x), - SP_Y_STR, LINEAR_UNIT(hotend_offset[e].y) + SP_Y_STR, LINEAR_UNIT(hotend_offset[e].y), + SP_Z_STR, p_float_t(LINEAR_UNIT(hotend_offset[e].z), 3) ); - SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(hotend_offset[e].z), 3); } } diff --git a/Marlin/src/gcode/config/M220.cpp b/Marlin/src/gcode/config/M220.cpp index c9070df803..0d1e204800 100644 --- a/Marlin/src/gcode/config/M220.cpp +++ b/Marlin/src/gcode/config/M220.cpp @@ -24,28 +24,26 @@ #include "../../module/motion.h" /** - * M220: Set speed percentage factor, aka "Feed Rate" + * M220: Set Feedrate Percentage * - * Parameters - * S : Set the feed rate percentage factor + * Parameters: + * None Report the current speed percentage factor + * S Set the feed rate percentage factor * - * Report the current speed percentage factor if no parameter is specified - * - * For MMU2 and MMU2S devices... - * B : Flag to back up the current factor - * R : Flag to restore the last-saved factor + * For MMU2 and MMU2S devices: + * B Back up the current factor + * R Restore the last-saved factor */ void GcodeSuite::M220() { + if (!parser.seen_any()) { + SERIAL_ECHOLNPGM("FR:", feedrate_percentage, "%"); + return; + } static int16_t backup_feedrate_percentage = 100; - if (parser.seen('B')) backup_feedrate_percentage = feedrate_percentage; - if (parser.seen('R')) feedrate_percentage = backup_feedrate_percentage; - + const int16_t now_feedrate_perc = feedrate_percentage; + if (parser.seen_test('R')) feedrate_percentage = backup_feedrate_percentage; + if (parser.seen_test('B')) backup_feedrate_percentage = now_feedrate_perc; if (parser.seenval('S')) feedrate_percentage = parser.value_int(); - if (!parser.seen_any()) { - SERIAL_ECHOPGM("FR:", feedrate_percentage); - SERIAL_CHAR('%'); - SERIAL_EOL(); - } } diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index e4ef3ab40b..24a179e54e 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -55,8 +55,10 @@ void GcodeSuite::M281() { } void GcodeSuite::M281_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_SERVO_ANGLES)); - LOOP_L_N(i, NUM_SERVOS) { + for (uint8_t i = 0; i < NUM_SERVOS; ++i) { switch (i) { default: break; #if ENABLED(SWITCHING_EXTRUDER) @@ -66,6 +68,9 @@ void GcodeSuite::M281_report(const bool forReplay/*=true*/) { #endif #elif ENABLED(SWITCHING_NOZZLE) case SWITCHING_NOZZLE_SERVO_NR: + #if ENABLED(SWITCHING_NOZZLE_TWO_SERVOS) + case SWITCHING_NOZZLE_E1_SERVO_NR: + #endif #elif ENABLED(BLTOUCH) || (HAS_Z_SERVO_PROBE && defined(Z_SERVO_ANGLES)) case Z_PROBE_SERVO_NR: #endif diff --git a/Marlin/src/gcode/config/M301.cpp b/Marlin/src/gcode/config/M301.cpp index fc9f1883d6..a47c03a8d4 100644 --- a/Marlin/src/gcode/config/M301.cpp +++ b/Marlin/src/gcode/config/M301.cpp @@ -28,22 +28,22 @@ #include "../../module/temperature.h" /** - * M301: Set PID parameters P I D (and optionally C, L) + * M301: Set Hotend PID * - * E[extruder] Default: 0 + * Set PID parameters P I D (and optionally C, L) * - * P[float] Kp term - * I[float] Ki term (unscaled) - * D[float] Kd term (unscaled) + * Parameters: + * E Default: 0 + * P Kp term + * I Ki term (unscaled) + * D Kd term (unscaled) * - * With PID_EXTRUSION_SCALING: + * With PID_EXTRUSION_SCALING: + * C Kc term + * L LPQ length * - * C[float] Kc term - * L[int] LPQ length - * - * With PID_FAN_SCALING: - * - * F[float] Kf term + * With PID_FAN_SCALING: + * F Kf term */ void GcodeSuite::M301() { // multi-extruder PID patch: M301 updates or prints a single extruder's PID values @@ -57,19 +57,18 @@ void GcodeSuite::M301() { if (e < HOTENDS) { // catch bad input value - if (parser.seenval('P')) PID_PARAM(Kp, e) = parser.value_float(); - if (parser.seenval('I')) PID_PARAM(Ki, e) = scalePID_i(parser.value_float()); - if (parser.seenval('D')) PID_PARAM(Kd, e) = scalePID_d(parser.value_float()); + if (parser.seenval('P')) SET_HOTEND_PID(Kp, e, parser.value_float()); + if (parser.seenval('I')) SET_HOTEND_PID(Ki, e, parser.value_float()); + if (parser.seenval('D')) SET_HOTEND_PID(Kd, e, parser.value_float()); #if ENABLED(PID_EXTRUSION_SCALING) - if (parser.seenval('C')) PID_PARAM(Kc, e) = parser.value_float(); + if (parser.seenval('C')) SET_HOTEND_PID(Kc, e, parser.value_float()); if (parser.seenval('L')) thermalManager.lpq_len = parser.value_int(); - NOMORE(thermalManager.lpq_len, LPQ_MAX_LEN); - NOLESS(thermalManager.lpq_len, 0); + LIMIT(thermalManager.lpq_len, 0, LPQ_MAX_LEN); #endif #if ENABLED(PID_FAN_SCALING) - if (parser.seenval('F')) PID_PARAM(Kf, e) = parser.value_float(); + if (parser.seenval('F')) SET_HOTEND_PID(Kf, e, parser.value_float()); #endif thermalManager.updatePID(); @@ -79,10 +78,13 @@ void GcodeSuite::M301() { } void GcodeSuite::M301_report(const bool forReplay/*=true*/ E_OPTARG(const int8_t eindex/*=-1*/)) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading(forReplay, F(STR_HOTEND_PID)); IF_DISABLED(HAS_MULTI_EXTRUDER, constexpr int8_t eindex = -1); HOTEND_LOOP() { if (e == eindex || eindex == -1) { + const hotend_pid_t &pid = thermalManager.temp_hotend[e].pid; report_echo_start(forReplay); SERIAL_ECHOPGM_P( #if ENABLED(PID_PARAMS_PER_HOTEND) @@ -90,16 +92,14 @@ void GcodeSuite::M301_report(const bool forReplay/*=true*/ E_OPTARG(const int8_t #else PSTR(" M301 P") #endif - , PID_PARAM(Kp, e) - , PSTR(" I"), unscalePID_i(PID_PARAM(Ki, e)) - , PSTR(" D"), unscalePID_d(PID_PARAM(Kd, e)) + , pid.p(), PSTR(" I"), pid.i(), PSTR(" D"), pid.d() ); #if ENABLED(PID_EXTRUSION_SCALING) - SERIAL_ECHOPGM_P(SP_C_STR, PID_PARAM(Kc, e)); + SERIAL_ECHOPGM_P(SP_C_STR, pid.c()); if (e == 0) SERIAL_ECHOPGM(" L", thermalManager.lpq_len); #endif #if ENABLED(PID_FAN_SCALING) - SERIAL_ECHOPGM(" F", PID_PARAM(Kf, e)); + SERIAL_ECHOPGM(" F", pid.f()); #endif SERIAL_EOL(); } diff --git a/Marlin/src/gcode/config/M302.cpp b/Marlin/src/gcode/config/M302.cpp index 9f4d569d7b..0648f3edca 100644 --- a/Marlin/src/gcode/config/M302.cpp +++ b/Marlin/src/gcode/config/M302.cpp @@ -25,12 +25,13 @@ #if ENABLED(PREVENT_COLD_EXTRUSION) #include "../gcode.h" -#include "../../module/temperature.h" -#if ENABLED(DWIN_LCD_PROUI) - #include "../../lcd/e3v2/proui/dwin_defines.h" +#if ENABLED(EXTENSIBLE_UI) + #include "../../lcd/extui/ui_api.h" #endif +#include "../../module/temperature.h" + /** * M302: Allow cold extrudes, or set the minimum extrude temperature * @@ -50,18 +51,17 @@ void GcodeSuite::M302() { const bool seen_S = parser.seen('S'); if (seen_S) { thermalManager.extrude_min_temp = parser.value_celsius(); - thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0); - TERN_(DWIN_LCD_PROUI, HMI_data.ExtMinT = thermalManager.extrude_min_temp); + TERN_(EXTENSIBLE_UI, ExtUI::onSetMinExtrusionTemp(thermalManager.extrude_min_temp)); } - if (parser.seen('P')) - thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0) || parser.value_bool(); - else if (!seen_S) { + const bool seen_P = parser.seen('P'); + if (seen_P || seen_S) { + thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0) || (seen_P && parser.value_bool()); + } + else { // Report current state SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Cold extrudes are "); - SERIAL_ECHOF(thermalManager.allow_cold_extrude ? F("en") : F("dis")); - SERIAL_ECHOLNPGM("abled (min temp ", thermalManager.extrude_min_temp, "C)"); + SERIAL_ECHOLN(F("Cold extrudes are "), thermalManager.allow_cold_extrude ? F("en") : F("dis"), F("abled (min temp "), thermalManager.extrude_min_temp, F("C)")); } } diff --git a/Marlin/src/gcode/config/M304.cpp b/Marlin/src/gcode/config/M304.cpp index c970288238..8201730afd 100644 --- a/Marlin/src/gcode/config/M304.cpp +++ b/Marlin/src/gcode/config/M304.cpp @@ -36,17 +36,19 @@ */ void GcodeSuite::M304() { if (!parser.seen("PID")) return M304_report(); - if (parser.seenval('P')) thermalManager.temp_bed.pid.Kp = parser.value_float(); - if (parser.seenval('I')) thermalManager.temp_bed.pid.Ki = scalePID_i(parser.value_float()); - if (parser.seenval('D')) thermalManager.temp_bed.pid.Kd = scalePID_d(parser.value_float()); + if (parser.seenval('P')) thermalManager.temp_bed.pid.set_Kp(parser.value_float()); + if (parser.seenval('I')) thermalManager.temp_bed.pid.set_Ki(parser.value_float()); + if (parser.seenval('D')) thermalManager.temp_bed.pid.set_Kd(parser.value_float()); } void GcodeSuite::M304_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_BED_PID)); - SERIAL_ECHOLNPGM( - " M304 P", thermalManager.temp_bed.pid.Kp - , " I", unscalePID_i(thermalManager.temp_bed.pid.Ki) - , " D", unscalePID_d(thermalManager.temp_bed.pid.Kd) + SERIAL_ECHOLNPGM(" M304" + " P", thermalManager.temp_bed.pid.p() + , " I", thermalManager.temp_bed.pid.i() + , " D", thermalManager.temp_bed.pid.d() ); } diff --git a/Marlin/src/gcode/config/M305.cpp b/Marlin/src/gcode/config/M305.cpp index e7746923b3..48d7cf1882 100644 --- a/Marlin/src/gcode/config/M305.cpp +++ b/Marlin/src/gcode/config/M305.cpp @@ -69,7 +69,7 @@ void GcodeSuite::M305() { SERIAL_ECHO_MSG("!Invalid Steinhart-Hart C coeff. (-0.01 < C < +0.01)"); } // If not setting then report parameters else if (t_index < 0) { // ...all user thermistors - LOOP_L_N(i, USER_THERMISTORS) + for (uint8_t i = 0; i < USER_THERMISTORS; ++i) thermalManager.M305_report(i); } else // ...one user thermistor diff --git a/Marlin/src/gcode/config/M309.cpp b/Marlin/src/gcode/config/M309.cpp index 577023292e..033f5731ed 100644 --- a/Marlin/src/gcode/config/M309.cpp +++ b/Marlin/src/gcode/config/M309.cpp @@ -36,17 +36,19 @@ */ void GcodeSuite::M309() { if (!parser.seen("PID")) return M309_report(); - if (parser.seen('P')) thermalManager.temp_chamber.pid.Kp = parser.value_float(); - if (parser.seen('I')) thermalManager.temp_chamber.pid.Ki = scalePID_i(parser.value_float()); - if (parser.seen('D')) thermalManager.temp_chamber.pid.Kd = scalePID_d(parser.value_float()); + if (parser.seenval('P')) thermalManager.temp_chamber.pid.set_Kp(parser.value_float()); + if (parser.seenval('I')) thermalManager.temp_chamber.pid.set_Ki(parser.value_float()); + if (parser.seenval('D')) thermalManager.temp_chamber.pid.set_Kd(parser.value_float()); } void GcodeSuite::M309_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_CHAMBER_PID)); - SERIAL_ECHOLNPGM( - " M309 P", thermalManager.temp_chamber.pid.Kp - , " I", unscalePID_i(thermalManager.temp_chamber.pid.Ki) - , " D", unscalePID_d(thermalManager.temp_chamber.pid.Kd) + SERIAL_ECHOLNPGM(" M309" + " P", thermalManager.temp_chamber.pid.p() + , " I", thermalManager.temp_chamber.pid.i() + , " D", thermalManager.temp_chamber.pid.d() ); } diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 688b94c9bf..9410fea136 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -25,7 +25,6 @@ #if ENABLED(PINS_DEBUGGING) #include "../gcode.h" -#include "../../MarlinCore.h" // for pin_is_protected #include "../../pins/pinsDebug.h" #include "../../module/endstops.h" @@ -61,36 +60,38 @@ inline void toggle_pins() { end = PARSED_PIN_INDEX('L', NUM_DIGITAL_PINS - 1), wait = parser.intval('W', 500); - LOOP_S_LE_N(i, start, end) { + for (uint8_t i = start; i <= end; ++i) { pin_t pin = GET_PIN_MAP_PIN_M43(i); - if (!VALID_PIN(pin)) continue; - if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) { - report_pin_state_extended(pin, ignore_protection, true, F("Untouched ")); + if (!isValidPin(pin)) continue; + if (M43_NEVER_TOUCH(i) || (!ignore_protection && marlin.pin_is_protected(pin))) { + printPinStateExt(pin, ignore_protection, true, F("Untouched ")); SERIAL_EOL(); } else { hal.watchdog_refresh(); - report_pin_state_extended(pin, ignore_protection, true, F("Pulsing ")); - #ifdef __STM32F1__ - const auto prior_mode = _GET_MODE(i); - #else - const bool prior_mode = GET_PINMODE(pin); - #endif + printPinStateExt(pin, ignore_protection, true, F("Pulsing ")); + const auto prior_mode = ( + #ifdef __STM32F1__ + _GET_MODE(i) + #else + getValidPinMode(pin) + #endif + ); #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO - if (pin == TEENSY_E2) { - SET_OUTPUT(TEENSY_E2); + if (pin == PIN_E2) { + SET_OUTPUT(PIN_E2); for (int16_t j = 0; j < repeat; j++) { - WRITE(TEENSY_E2, LOW); safe_delay(wait); - WRITE(TEENSY_E2, HIGH); safe_delay(wait); - WRITE(TEENSY_E2, LOW); safe_delay(wait); + WRITE(PIN_E2, LOW); safe_delay(wait); + WRITE(PIN_E2, HIGH); safe_delay(wait); + WRITE(PIN_E2, LOW); safe_delay(wait); } } - else if (pin == TEENSY_E3) { - SET_OUTPUT(TEENSY_E3); + else if (pin == PIN_E3) { + SET_OUTPUT(PIN_E3); for (int16_t j = 0; j < repeat; j++) { - WRITE(TEENSY_E3, LOW); safe_delay(wait); - WRITE(TEENSY_E3, HIGH); safe_delay(wait); - WRITE(TEENSY_E3, LOW); safe_delay(wait); + WRITE(PIN_E3, LOW); safe_delay(wait); + WRITE(PIN_E3, HIGH); safe_delay(wait); + WRITE(PIN_E3, LOW); safe_delay(wait); } } else @@ -118,7 +119,7 @@ inline void toggle_pins() { inline void servo_probe_test() { - #if !(NUM_SERVOS > 0 && HAS_SERVO_0) + #if !HAS_SERVO_0 SERIAL_ERROR_MSG("SERVO not set up."); @@ -139,87 +140,76 @@ inline void servo_probe_test() { bool deploy_state = false, stow_state; #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #define PROBE_TEST_PIN Z_MIN_PIN - constexpr bool probe_inverting = Z_MIN_ENDSTOP_INVERTING; - - SERIAL_ECHOLNPGM(". Probe Z_MIN_PIN: ", PROBE_TEST_PIN); - SERIAL_ECHOPGM(". Z_MIN_ENDSTOP_INVERTING: "); - + #define _PROBE_PREF "Z_MIN" #else - #define PROBE_TEST_PIN Z_MIN_PROBE_PIN - constexpr bool probe_inverting = Z_MIN_PROBE_ENDSTOP_INVERTING; - - SERIAL_ECHOLNPGM(". Probe Z_MIN_PROBE_PIN: ", PROBE_TEST_PIN); - SERIAL_ECHOPGM( ". Z_MIN_PROBE_ENDSTOP_INVERTING: "); - + #define _PROBE_PREF "Z_MIN_PROBE" #endif - serialprint_truefalse(probe_inverting); + SERIAL_ECHOLNPGM(". Probe " _PROBE_PREF "_PIN: ", PROBE_TEST_PIN); + serial_ternary(F(". " _PROBE_PREF "_ENDSTOP_HIT_STATE: "), PROBE_HIT_STATE, F("HIGH"), F("LOW")); SERIAL_EOL(); SET_INPUT_PULLUP(PROBE_TEST_PIN); - // First, check for a probe that recognizes an advanced BLTouch sequence. - // In addition to STOW and DEPLOY, it uses SW MODE (and RESET in the beginning) - // to see if this is one of the following: BLTOUCH Classic 1.2, 1.3, or - // BLTouch Smart 1.0, 2.0, 2.2, 3.0, 3.1. But only if the user has actually - // configured a BLTouch as being present. If the user has not configured this, - // the BLTouch will be detected in the last phase of these tests (see further on). - bool blt = false; - // This code will try to detect a BLTouch probe or clone + /** + * This code will try to detect a BLTouch probe or clone. + * First, check for a probe that recognizes an advanced BLTouch sequence. + * In addition to STOW and DEPLOY, it uses SW MODE (and RESET in the beginning) + * to see if this is one of the following: BLTOUCH Classic 1.2, 1.3, or + * BLTouch Smart 1.0, 2.0, 2.2, 3.0, 3.1. But only if the user has actually + * configured a BLTouch as being present. If the user has not configured this, + * the BLTouch will be detected in the last phase of these tests (see further on). + */ #if ENABLED(BLTOUCH) - SERIAL_ECHOLNPGM(". Check for BLTOUCH"); - bltouch._reset(); - bltouch._stow(); - if (probe_inverting == READ(PROBE_TEST_PIN)) { - bltouch._set_SW_mode(); - if (probe_inverting != READ(PROBE_TEST_PIN)) { - bltouch._deploy(); - if (probe_inverting == READ(PROBE_TEST_PIN)) { - bltouch._stow(); - SERIAL_ECHOLNPGM("= BLTouch Classic 1.2, 1.3, Smart 1.0, 2.0, 2.2, 3.0, 3.1 detected."); - // Check for a 3.1 by letting the user trigger it, later - blt = true; - } - } - } + bool blt = false; + do { + SERIAL_ECHOLNPGM(". Check for BLTOUCH"); + bltouch._reset(); + bltouch._stow(); if ( PROBE_TRIGGERED()) break; + bltouch._set_SW_mode(); if (!PROBE_TRIGGERED()) break; + bltouch._deploy(); if ( PROBE_TRIGGERED()) break; + bltouch._stow(); + SERIAL_ECHOLNPGM("= BLTouch Classic 1.2, 1.3, Smart 1.0, 2.0, 2.2, 3.0, 3.1 detected."); + blt = true; // Check for a 3.1 by letting the user trigger it, later + } while(0); + #else + static constexpr bool blt = false; #endif // The following code is common to all kinds of servo probes. // Since it could be a real servo or a BLTouch (any kind) or a clone, // use only "common" functions - i.e. SERVO_MOVE. No bltouch.xxxx stuff. - // If it is already recognised as a being a BLTouch, no need for this test + // If it is already recognized as a being a BLTouch, no need for this test if (!blt) { // DEPLOY and STOW 4 times and see if the signal follows // Then it is a mechanical switch - uint8_t i = 0; SERIAL_ECHOLNPGM(". Deploy & stow 4 times"); - do { + for (uint8_t i = 0; i < 4; ++i) { servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy safe_delay(500); deploy_state = READ(PROBE_TEST_PIN); servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow safe_delay(500); stow_state = READ(PROBE_TEST_PIN); - } while (++i < 4); + } - if (probe_inverting != deploy_state) SERIAL_ECHOLNPGM("WARNING: INVERTING setting probably backwards."); + if (PROBE_HIT_STATE == deploy_state) SERIAL_ECHOLNPGM("WARNING: " _PROBE_PREF "_ENDSTOP_HIT_STATE is probably wrong."); if (deploy_state != stow_state) { SERIAL_ECHOLNPGM("= Mechanical Switch detected"); if (deploy_state) { - SERIAL_ECHOLNPGM(" DEPLOYED state: HIGH (logic 1)", - " STOWED (triggered) state: LOW (logic 0)"); + SERIAL_ECHOLNPGM(". DEPLOYED state: HIGH (logic 1)\n" + ". STOWED (triggered) state: LOW (logic 0)"); } else { - SERIAL_ECHOLNPGM(" DEPLOYED state: LOW (logic 0)", - " STOWED (triggered) state: HIGH (logic 1)"); + SERIAL_ECHOLNPGM(". DEPLOYED state: LOW (logic 0)\n" + ". STOWED (triggered) state: HIGH (logic 1)"); } #if ENABLED(BLTOUCH) - SERIAL_ECHOLNPGM("FAIL: BLTOUCH enabled - Set up this device as a Servo Probe with INVERTING set to 'true'."); + SERIAL_ECHOLNPGM("FAIL: Can't enable BLTOUCH. Check your settings."); #endif return; } @@ -302,9 +292,7 @@ void GcodeSuite::M43() { // 'E' Enable or disable endstop monitoring and return if (parser.seen('E')) { endstops.monitor_flag = parser.value_bool(); - SERIAL_ECHOPGM("endstop monitor "); - SERIAL_ECHOF(endstops.monitor_flag ? F("en") : F("dis")); - SERIAL_ECHOLNPGM("abled"); + SERIAL_ECHOLN(F("endstop monitor "), endstops.monitor_flag ? F("en") : F("dis"), F("abled")); return; } @@ -313,72 +301,104 @@ void GcodeSuite::M43() { // 'P' Get the range of pins to test or watch uint8_t first_pin = PARSED_PIN_INDEX('P', 0), - last_pin = parser.seenval('P') ? first_pin : TERN(HAS_HIGH_ANALOG_PINS, NUM_DIGITAL_PINS, NUMBER_PINS_TOTAL) - 1; + last_pin = parser.seenval('L') ? PARSED_PIN_INDEX('L', 0) : (parser.seenval('P') ? first_pin : (NUMBER_PINS_TOTAL) - 1); - if (first_pin > last_pin) return; + NOMORE(first_pin, (NUMBER_PINS_TOTAL) - 1); + NOMORE(last_pin, (NUMBER_PINS_TOTAL) - 1); + + if (first_pin > last_pin) { + const uint8_t f = first_pin; + first_pin = last_pin; + last_pin = f; + } // 'I' to ignore protected pins const bool ignore_protection = parser.boolval('I'); // 'W' Watch until click, M108, or reset if (parser.boolval('W')) { - SERIAL_ECHOLNPGM("Watching pins"); #ifdef ARDUINO_ARCH_SAM NOLESS(first_pin, 2); // Don't hijack the UART pins #endif - uint8_t pin_state[last_pin - first_pin + 1]; - LOOP_S_LE_N(i, first_pin, last_pin) { + + const uint8_t pin_count = last_pin - first_pin + 1; + uint8_t pin_state[pin_count]; + bool can_watch = false; + for (uint8_t i = first_pin; i <= last_pin; ++i) { pin_t pin = GET_PIN_MAP_PIN_M43(i); - if (!VALID_PIN(pin)) continue; - if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue; + if (!isValidPin(pin)) continue; + if (M43_NEVER_TOUCH(i) || (!ignore_protection && marlin.pin_is_protected(pin))) continue; + can_watch = true; pinMode(pin, INPUT_PULLUP); delay(1); /* - if (IS_ANALOG(pin)) - pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...] + if (isAnalogPin(pin)) + pin_state[pin - first_pin] = analogRead(digitalPinToAnalogIndex(pin)); // int16_t pin_state[...] else //*/ pin_state[i - first_pin] = extDigitalRead(pin); } + const bool multipin = (pin_count > 1); + + if (!can_watch) { + SERIAL_ECHOPGM("Specified pin"); + SERIAL_ECHOPGM_P(multipin ? PSTR("s are") : PSTR(" is")); + SERIAL_ECHOLNPGM(" protected. Use 'I' to override."); + return; + } + + // "Watching pin(s) # - #" + SERIAL_ECHOPGM("Watching pin"); + if (multipin) SERIAL_CHAR('s'); + SERIAL_CHAR(' '); SERIAL_ECHO(first_pin); + if (multipin) SERIAL_ECHOPGM(" - ", last_pin); + SERIAL_EOL(); + #if HAS_RESUME_CONTINUE KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; - TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, F("M43 Wait Called"), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("M43 Wait Called"))); + marlin.wait_start(); + TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(F("M43 Waiting..."))); + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onUserConfirmRequired(F("M43 Waiting...")); + #else + LCD_MESSAGE(MSG_USERWAIT); + #endif #endif for (;;) { - LOOP_S_LE_N(i, first_pin, last_pin) { - pin_t pin = GET_PIN_MAP_PIN_M43(i); - if (!VALID_PIN(pin)) continue; - if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue; + for (uint8_t i = first_pin; i <= last_pin; ++i) { + const pin_t pin = GET_PIN_MAP_PIN_M43(i); + if (!isValidPin(pin)) continue; + if (M43_NEVER_TOUCH(i) || (!ignore_protection && marlin.pin_is_protected(pin))) continue; const byte val = /* - IS_ANALOG(pin) - ? analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)) : // int16_t val + isAnalogPin(pin) + ? analogRead(digitalPinToAnalogIndex(pin)) : // int16_t val : //*/ extDigitalRead(pin); if (val != pin_state[i - first_pin]) { - report_pin_state_extended(pin, ignore_protection, false); + printPinStateExt(pin, ignore_protection, true); pin_state[i - first_pin] = val; } } #if HAS_RESUME_CONTINUE ui.update(); - if (!wait_for_user) break; + if (!marlin.wait_for_user) break; #endif safe_delay(200); } + + TERN_(HAS_RESUME_CONTINUE, ui.reset_status()); } else { // Report current state of selected pin(s) - LOOP_S_LE_N(i, first_pin, last_pin) { - pin_t pin = GET_PIN_MAP_PIN_M43(i); - if (VALID_PIN(pin)) report_pin_state_extended(pin, ignore_protection, true); + for (uint8_t i = first_pin; i <= last_pin; ++i) { + const pin_t pin = GET_PIN_MAP_PIN_M43(i); + if (isValidPin(pin)) printPinStateExt(pin, ignore_protection, true); } } } diff --git a/Marlin/src/gcode/config/M550.cpp b/Marlin/src/gcode/config/M550.cpp new file mode 100644 index 0000000000..ed7dc49159 --- /dev/null +++ b/Marlin/src/gcode/config/M550.cpp @@ -0,0 +1,58 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(CONFIGURABLE_MACHINE_NAME) + +#include "../gcode.h" +#include "../../lcd/marlinui.h" + +/** + * M550: Set machine name + * + * Parameters: + * P "" Set the name using the 'P' parameter (RepRapFirmware) + * "" Set the name using the "string" parameter + */ +void GcodeSuite::M550() { + bool did_set = true; + + if (parser.seenval('P')) + marlin.machine_name = parser.value_string(); + else if (TERN(GCODE_QUOTED_STRINGS, false, parser.seen('P'))) + marlin.machine_name = parser.string_arg[0] == 'P' ? &parser.string_arg[1] : parser.string_arg; + else if (parser.has_string()) + marlin.machine_name = parser.string_arg; + else + did_set = false; + + if (did_set) { + marlin.machine_name.trim(); + ui.reset_status(false); + } + else + SERIAL_ECHOLNPGM("RepRap name: ", &marlin.machine_name); + +} + +#endif // CONFIGURABLE_MACHINE_NAME diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp index 2c12428d98..dd8f8addb5 100644 --- a/Marlin/src/gcode/config/M575.cpp +++ b/Marlin/src/gcode/config/M575.cpp @@ -51,25 +51,25 @@ void GcodeSuite::M575() { switch (baud) { case 2400: case 9600: case 19200: case 38400: case 57600: case 115200: case 250000: case 500000: case 1000000: { + SERIAL_FLUSH(); + const int8_t port = parser.intval('P', -99); const bool set1 = (port == -99 || port == 0); - if (set1) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(0), " baud rate set to ", baud); + if (set1) { MYSERIAL1.end(); MYSERIAL1.begin(baud); } #if HAS_MULTI_SERIAL const bool set2 = (port == -99 || port == 1); - if (set2) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(1), " baud rate set to ", baud); + if (set2) { MYSERIAL2.end(); MYSERIAL2.begin(baud); } #ifdef SERIAL_PORT_3 const bool set3 = (port == -99 || port == 2); - if (set3) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(2), " baud rate set to ", baud); + if (set3) { MYSERIAL3.end(); MYSERIAL3.begin(baud); } #endif #endif - SERIAL_FLUSH(); - - if (set1) { MYSERIAL1.end(); MYSERIAL1.begin(baud); } + if (set1) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(0), " baud rate set to ", baud); #if HAS_MULTI_SERIAL - if (set2) { MYSERIAL2.end(); MYSERIAL2.begin(baud); } + if (set2) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(1), " baud rate set to ", baud); #ifdef SERIAL_PORT_3 - if (set3) { MYSERIAL3.end(); MYSERIAL3.begin(baud); } + if (set3) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(2), " baud rate set to ", baud); #endif #endif diff --git a/Marlin/src/gcode/config/M672.cpp b/Marlin/src/gcode/config/M672.cpp index 257b49471f..064d05d0b6 100644 --- a/Marlin/src/gcode/config/M672.cpp +++ b/Marlin/src/gcode/config/M672.cpp @@ -54,7 +54,7 @@ // b3 b2 b1 b0 ~b0 ... lo bits, NOT last bit // void M672_send(uint8_t b) { // bit rate requirement: 1kHz +/- 30% - LOOP_L_N(bits, 14) { + for (uint8_t bits = 0; bits < 14; ++bits) { switch (bits) { default: { OUT_WRITE(SMART_EFFECTOR_MOD_PIN, !!(b & 0x80)); b <<= 1; break; } // send bit, shift next into place case 7: diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index c7610b83a9..48c3c5f2f0 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -20,6 +20,10 @@ * */ +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(EDITABLE_STEPS_PER_UNIT) + #include "../gcode.h" #include "../../module/planner.h" @@ -37,6 +41,7 @@ * H - Specify micro-steps to use. Best guess if not supplied. * L - Desired layer height in current units. Nearest good heights are shown. */ + void GcodeSuite::M92() { const int8_t target_extruder = get_target_extruder_from_command(); @@ -55,7 +60,7 @@ void GcodeSuite::M92() { const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder))); if (value < 20) { float factor = planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] / value; // increase e constants if M92 E14 is given for netfab. - #if HAS_CLASSIC_JERK && HAS_CLASSIC_E_JERK + #if ALL(CLASSIC_JERK, HAS_CLASSIC_E_JERK) planner.max_jerk.e *= factor; #endif planner.settings.max_feedrate_mm_s[E_AXIS_N(target_extruder)] *= factor; @@ -82,7 +87,7 @@ void GcodeSuite::M92() { if (wanted) { const float best = uint16_t(wanted / z_full_step_mm) * z_full_step_mm; SERIAL_ECHOPGM(", best:[", best); - if (best != wanted) { SERIAL_CHAR(','); SERIAL_DECIMAL(best + z_full_step_mm); } + if (best != wanted) { SERIAL_ECHO(C(','), best + z_full_step_mm); } SERIAL_CHAR(']'); } SERIAL_ECHOLNPGM(" }"); @@ -91,25 +96,33 @@ void GcodeSuite::M92() { } void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_STEPS_PER_UNIT)); - SERIAL_ECHOPGM_P(LIST_N(DOUBLE(NUM_AXES), - PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), - SP_I_STR, I_AXIS_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), - SP_J_STR, J_AXIS_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), - SP_K_STR, K_AXIS_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]), - SP_U_STR, U_AXIS_UNIT(planner.settings.axis_steps_per_mm[U_AXIS]), - SP_V_STR, V_AXIS_UNIT(planner.settings.axis_steps_per_mm[V_AXIS]), - SP_W_STR, W_AXIS_UNIT(planner.settings.axis_steps_per_mm[W_AXIS]) - )); + #if NUM_AXES + #define PRINT_EOL + SERIAL_ECHOPGM_P(NUM_AXIS_PAIRED_LIST( + PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), + SP_I_STR, I_AXIS_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), + SP_J_STR, J_AXIS_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), + SP_K_STR, K_AXIS_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]), + SP_U_STR, U_AXIS_UNIT(planner.settings.axis_steps_per_mm[U_AXIS]), + SP_V_STR, V_AXIS_UNIT(planner.settings.axis_steps_per_mm[V_AXIS]), + SP_W_STR, W_AXIS_UNIT(planner.settings.axis_steps_per_mm[W_AXIS]) + )); + #endif + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + #define PRINT_EOL SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); #endif - SERIAL_EOL(); + + if (ENABLED(PRINT_EOL)) SERIAL_EOL(); #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { + for (uint8_t i = 0; i < E_STEPPERS; ++i) { if (e >= 0 && i != e) continue; report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( @@ -121,3 +134,5 @@ void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/ UNUSED(e); #endif } + +#endif // EDITABLE_STEPS_PER_UNIT diff --git a/Marlin/src/gcode/control/M108_M112_M410.cpp b/Marlin/src/gcode/control/M108_M112_M410.cpp index 39f9c04e19..e2ca9b2247 100644 --- a/Marlin/src/gcode/control/M108_M112_M410.cpp +++ b/Marlin/src/gcode/control/M108_M112_M410.cpp @@ -21,26 +21,21 @@ */ #include "../../inc/MarlinConfig.h" - -#if DISABLED(EMERGENCY_PARSER) - #include "../gcode.h" -#include "../../MarlinCore.h" // for wait_for_heatup, kill, M112_KILL_STR #include "../../module/motion.h" // for quickstop_stepper /** * M108: Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature. */ void GcodeSuite::M108() { - TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); - wait_for_heatup = false; + marlin.end_waiting(); } /** * M112: Full Shutdown */ void GcodeSuite::M112() { - kill(FPSTR(M112_KILL_STR), nullptr, true); + marlin.kill(FPSTR(M112_KILL_STR), nullptr, true); } /** @@ -52,5 +47,3 @@ void GcodeSuite::M112() { void GcodeSuite::M410() { quickstop_stepper(); } - -#endif // !EMERGENCY_PARSER diff --git a/Marlin/src/gcode/control/M10-M11.cpp b/Marlin/src/gcode/control/M10_M11.cpp similarity index 95% rename from Marlin/src/gcode/control/M10-M11.cpp rename to Marlin/src/gcode/control/M10_M11.cpp index d5a69dcfcc..8fd299c546 100644 --- a/Marlin/src/gcode/control/M10-M11.cpp +++ b/Marlin/src/gcode/control/M10_M11.cpp @@ -20,6 +20,11 @@ * */ +/** + * gcode/control/M10_M11.cpp + * Air Evacuation + */ + #include "../../inc/MarlinConfig.h" #if ENABLED(AIR_EVACUATION) diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp index a92d334ae9..a8e549b69d 100644 --- a/Marlin/src/gcode/control/M111.cpp +++ b/Marlin/src/gcode/control/M111.cpp @@ -20,6 +20,7 @@ * */ +#include "../../inc/MarlinConfig.h" #include "../gcode.h" /** @@ -27,18 +28,25 @@ */ void GcodeSuite::M111() { if (parser.seenval('S')) marlin_debug_flags = parser.value_byte(); - - static PGMSTR(str_debug_1, STR_DEBUG_ECHO); - static PGMSTR(str_debug_2, STR_DEBUG_INFO); - static PGMSTR(str_debug_4, STR_DEBUG_ERRORS); + #if ENABLED(DEBUG_FLAGS_GCODE) + static PGMSTR(str_debug_1, STR_DEBUG_ECHO); + static PGMSTR(str_debug_2, STR_DEBUG_INFO); + static PGMSTR(str_debug_4, STR_DEBUG_ERRORS); + #endif static PGMSTR(str_debug_8, STR_DEBUG_DRYRUN); - static PGMSTR(str_debug_16, STR_DEBUG_COMMUNICATION); + #if ENABLED(DEBUG_FLAGS_GCODE) + static PGMSTR(str_debug_16, STR_DEBUG_COMMUNICATION); + #endif #if ENABLED(DEBUG_LEVELING_FEATURE) static PGMSTR(str_debug_detail, STR_DEBUG_DETAIL); #endif static PGM_P const debug_strings[] PROGMEM = { - str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16, + TERN(DEBUG_FLAGS_GCODE, str_debug_1, nullptr), + TERN(DEBUG_FLAGS_GCODE, str_debug_2, nullptr), + TERN(DEBUG_FLAGS_GCODE, str_debug_4, nullptr), + str_debug_8, + TERN(DEBUG_FLAGS_GCODE, str_debug_16, nullptr), TERN_(DEBUG_LEVELING_FEATURE, str_debug_detail) }; @@ -46,32 +54,30 @@ void GcodeSuite::M111() { SERIAL_ECHOPGM(STR_DEBUG_PREFIX); if (marlin_debug_flags) { uint8_t comma = 0; - LOOP_L_N(i, COUNT(debug_strings)) { - if (TEST(marlin_debug_flags, i)) { + for (uint8_t i = 0; i < COUNT(debug_strings); ++i) { + PGM_P const pstr = (PGM_P)pgm_read_ptr(&debug_strings[i]); + if (pstr && TEST(marlin_debug_flags, i)) { if (comma++) SERIAL_CHAR(','); - SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&debug_strings[i])); + SERIAL_ECHOPGM_P(pstr); } } } else { SERIAL_ECHOPGM(STR_DEBUG_OFF); - #if !defined(__AVR__) || !defined(USBCON) + #if !(defined(__AVR__) && defined(USBCON)) #if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS) SERIAL_ECHOPGM("\nBuffer Overruns: ", MYSERIAL1.buffer_overruns()); #endif - #if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS) SERIAL_ECHOPGM("\nFraming Errors: ", MYSERIAL1.framing_errors()); #endif - #if ENABLED(SERIAL_STATS_DROPPED_RX) SERIAL_ECHOPGM("\nDropped bytes: ", MYSERIAL1.dropped()); #endif - #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) SERIAL_ECHOPGM("\nMax RX Queue Size: ", MYSERIAL1.rxMaxEnqueued()); #endif - #endif // !__AVR__ || !USBCON + #endif // !(__AVR__ && USBCON) } SERIAL_EOL(); } diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index 4ff48568fa..90563889f3 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -48,17 +48,19 @@ inline stepper_flags_t selected_axis_bits() { selected.bits = e_axis_mask; } #endif - selected.bits |= NUM_AXIS_GANG( - (parser.seen_test('X') << X_AXIS), - | (parser.seen_test('Y') << Y_AXIS), - | (parser.seen_test('Z') << Z_AXIS), - | (parser.seen_test(AXIS4_NAME) << I_AXIS), - | (parser.seen_test(AXIS5_NAME) << J_AXIS), - | (parser.seen_test(AXIS6_NAME) << K_AXIS), - | (parser.seen_test(AXIS7_NAME) << U_AXIS), - | (parser.seen_test(AXIS8_NAME) << V_AXIS), - | (parser.seen_test(AXIS9_NAME) << W_AXIS) - ); + #if NUM_AXES + selected.bits |= NUM_AXIS_GANG( + (parser.seen_test('X') << X_AXIS), + | (parser.seen_test('Y') << Y_AXIS), + | (parser.seen_test('Z') << Z_AXIS), + | (parser.seen_test(AXIS4_NAME) << I_AXIS), + | (parser.seen_test(AXIS5_NAME) << J_AXIS), + | (parser.seen_test(AXIS6_NAME) << K_AXIS), + | (parser.seen_test(AXIS7_NAME) << U_AXIS), + | (parser.seen_test(AXIS8_NAME) << V_AXIS), + | (parser.seen_test(AXIS9_NAME) << W_AXIS) + ); + #endif return selected; } @@ -71,12 +73,12 @@ void do_enable(const stepper_flags_t to_enable) { if (!shall_enable) return; // All specified axes already enabled? - ena_mask_t also_enabled = 0; // Track steppers enabled due to overlap + ena_mask_t also_enabled = 0; // Track steppers enabled due to overlap // Enable all flagged axes LOOP_NUM_AXES(a) { if (TEST(shall_enable, a)) { - stepper.enable_axis(AxisEnum(a)); // Mark and enable the requested axis + stepper.enable_axis((AxisEnum)a); // Mark and enable the requested axis DEBUG_ECHOLNPGM("Enabled ", AXIS_CHAR(a), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... Enabled: ", hex_word(stepper.axis_enabled.bits)); also_enabled |= enable_overlap[a]; } @@ -151,7 +153,7 @@ void try_to_disable(const stepper_flags_t to_disable) { LOOP_NUM_AXES(a) if (TEST(to_disable.bits, a)) { DEBUG_ECHOPGM("Try to disable ", AXIS_CHAR(a), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... "); - if (stepper.disable_axis(AxisEnum(a))) { // Mark the requested axis and request to disable + if (stepper.disable_axis((AxisEnum)a)) { // Mark the requested axis and request to disable DEBUG_ECHOPGM("OK"); still_enabled &= ~(_BV(a) | enable_overlap[a]); // If actually disabled, clear one or more tracked bits } @@ -212,7 +214,7 @@ void try_to_disable(const stepper_flags_t to_disable) { void GcodeSuite::M18_M84() { if (parser.seenval('S')) { reset_stepper_timeout(); - #if HAS_DISABLE_INACTIVE_AXIS + #if HAS_DISABLE_IDLE_AXES const millis_t ms = parser.value_millis_from_seconds(); #if LASER_SAFETY_TIMEOUT_MS > 0 if (ms && ms <= LASER_SAFETY_TIMEOUT_MS) { diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index 95ae052a7b..e51a9d5297 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -40,15 +40,16 @@ void GcodeSuite::M211() { } void GcodeSuite::M211_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_SOFT_ENDSTOPS)); - SERIAL_ECHOPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; "); - serialprintln_onoff(soft_endstop._enabled); + SERIAL_ECHOLNPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; ", ON_OFF(soft_endstop._enabled)); report_echo_start(forReplay); const xyz_pos_t l_soft_min = soft_endstop.min.asLogical(), l_soft_max = soft_endstop.max.asLogical(); - print_pos(l_soft_min, F(STR_SOFT_MIN), F(" ")); - print_pos(l_soft_max, F(STR_SOFT_MAX)); + print_xyz(l_soft_min, F(STR_SOFT_MIN), F(" ")); + print_xyz(l_soft_max, F(STR_SOFT_MAX)); } #endif // HAS_SOFTWARE_ENDSTOPS diff --git a/Marlin/src/gcode/control/M226.cpp b/Marlin/src/gcode/control/M226.cpp index 4eb3db4bc3..921ce0d4c2 100644 --- a/Marlin/src/gcode/control/M226.cpp +++ b/Marlin/src/gcode/control/M226.cpp @@ -25,7 +25,6 @@ #if ENABLED(DIRECT_PIN_CONTROL) #include "../gcode.h" -#include "../../MarlinCore.h" // for pin_is_protected and idle() #include "../../module/planner.h" void protected_pin_err(); @@ -40,7 +39,7 @@ void GcodeSuite::M226() { const pin_t pin = GET_PIN_MAP_PIN(pin_number); if (WITHIN(pin_state, -1, 1) && pin > -1) { - if (pin_is_protected(pin)) + if (marlin.pin_is_protected(pin)) protected_pin_err(); else { int target = LOW; @@ -51,7 +50,7 @@ void GcodeSuite::M226() { case 0: target = LOW; break; case -1: target = !extDigitalRead(pin); break; } - while (int(extDigitalRead(pin)) != target) idle(); + while (int(extDigitalRead(pin)) != target) marlin.idle(); } } // pin_state -1 0 1 && pin > -1 } // parser.seen('P') diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index 5d5d44e8bf..9b6a2fb2f7 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -32,24 +32,22 @@ * Laser: * M3 - Laser ON/Power (Ramped power) * M4 - Laser ON/Power (Ramped power) - * M5 - Set power output to 0 (leaving inline mode unchanged). * * M3I - Enable continuous inline power to be processed by the planner, with power * calculated and set in the planner blocks, processed inline during stepping. - * Within inline mode M3 S-Values will set the power for the next moves e.g. G1 X10 Y10 powers on with the last S-Value. + * In inline mode M3 S-Values will set the power for the next moves. + * (e.g., G1 X10 Y10 powers on with the last S-Value.) * M3I must be set before using planner-synced M3 inline S-Values (LASER_POWER_SYNC). * * M4I - Set dynamic mode which calculates laser power OCR based on the current feedrate. * - * M5I - Clear inline mode and set power to 0. - * * Spindle: * M3 - Spindle ON (Clockwise) * M4 - Spindle ON (Counter-clockwise) - * M5 - Spindle OFF * * Parameters: * S - Set power. S0 will turn the spindle/laser off. + * O - Set power in PWM units 0-255 * * If no PWM pin is defined then M3/M4 just turns it on or off. * @@ -92,19 +90,19 @@ void GcodeSuite::M3_M4(const bool is_M4) { #endif auto get_s_power = [] { - float u; if (parser.seenval('S')) { const float v = parser.value_float(); - u = TERN(LASER_POWER_TRAP, v, cutter.power_to_range(v)); + cutter.menuPower = cutter.unitPower = TERN(LASER_POWER_TRAP, constrain( v, 0, CUTTER_POWER_MAX), cutter.power_to_range(v)); + } + else if (parser.seenval('O')) { // pwr in PWM units + const float v = parser.value_float(); + cutter.menuPower = cutter.unitPower = CUTTER_PWM_TO_SPWR(constrain(v, 0, 255)); } else if (cutter.cutter_mode == CUTTER_MODE_STANDARD) - u = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); - - cutter.menuPower = cutter.unitPower = u; + cutter.menuPower = cutter.unitPower = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); // PWM not implied, power converted to OCR from unit definition and on/off if not PWM. - cutter.power = TERN(SPINDLE_LASER_USE_PWM, cutter.upower_to_ocr(u), u > 0 ? 255 : 0); - return u; + cutter.power = TERN(SPINDLE_LASER_USE_PWM, cutter.upower_to_ocr(cutter.unitPower), cutter.unitPower > 0 ? 255 : 0); }; if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS || cutter.cutter_mode == CUTTER_MODE_DYNAMIC) { // Laser power in inline mode @@ -138,6 +136,13 @@ void GcodeSuite::M3_M4(const bool is_M4) { /** * M5 - Cutter OFF (when moves are complete) + * + * Laser: + * M5 - Set power output to 0 (leaving inline mode unchanged). + * M5I - Clear inline mode and set power to 0. + * + * Spindle: + * M5 - Spindle OFF */ void GcodeSuite::M5() { planner.synchronize(); diff --git a/Marlin/src/gcode/control/M350_M351.cpp b/Marlin/src/gcode/control/M350_M351.cpp index ac6b5a329b..76753b2ea9 100644 --- a/Marlin/src/gcode/control/M350_M351.cpp +++ b/Marlin/src/gcode/control/M350_M351.cpp @@ -27,11 +27,8 @@ #include "../gcode.h" #include "../../module/stepper.h" -#if NUM_AXES == XYZ && EXTRUDERS >= 1 +#if NUM_AXES == 3 && EXTRUDERS >= 1 #define HAS_M350_B_PARAM 1 // "5th axis" (after E0) for an original XYZEB setup. - #if AXIS_COLLISION('B') - #error "M350 parameter 'B' collision with axis name." - #endif #endif /** diff --git a/Marlin/src/gcode/control/M380_M381.cpp b/Marlin/src/gcode/control/M380_M381.cpp index 6bcec891e2..20d24484ed 100644 --- a/Marlin/src/gcode/control/M380_M381.cpp +++ b/Marlin/src/gcode/control/M380_M381.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) +#if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) #include "../gcode.h" #include "../../feature/solenoid.h" diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 1b3a29d100..717b0695a4 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -25,7 +25,6 @@ #if ENABLED(DIRECT_PIN_CONTROL) #include "../gcode.h" -#include "../../MarlinCore.h" // for pin_is_protected #if HAS_FAN #include "../../module/temperature.h" @@ -43,16 +42,18 @@ void protected_pin_err() { } /** - * M42: Change pin status via GCode + * M42: Change pin status via G-Code * - * P Pin number (LED if omitted) - * For LPC1768 specify pin P1_02 as M42 P102, - * P1_20 as M42 P120, etc. + * Parameters: + * P Pin number (LED if omitted) + * For LPC1768 specify pin P1_02 as M42 P102, + * P1_20 as M42 P120, etc. * - * S Pin status from 0 - 255 - * I Flag to ignore Marlin's pin protection + * S Pin status from 0-255 + * I Flag to ignore Marlin's pin protection * - * T Pin mode: 0=INPUT 1=OUTPUT 2=INPUT_PULLUP 3=INPUT_PULLDOWN + * T Pin mode: 0=INPUT | 1=OUTPUT | 2=INPUT_PULLUP | 3=INPUT_PULLDOWN + * 4=INPUT_ANALOG | 5=OUTPUT_OPEN_DRAIN */ void GcodeSuite::M42() { const int pin_index = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN)); @@ -60,7 +61,7 @@ void GcodeSuite::M42() { const pin_t pin = GET_PIN_MAP_PIN(pin_index); - if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err(); + if (!parser.boolval('I') && marlin.pin_is_protected(pin)) return protected_pin_err(); bool avoidWrite = false; if (parser.seenval('T')) { @@ -77,7 +78,7 @@ void GcodeSuite::M42() { #ifdef OUTPUT_OPEN_DRAIN case 5: pinMode(pin, OUTPUT_OPEN_DRAIN); break; #endif - default: SERIAL_ECHOLNPGM("Invalid Pin Mode"); return; + default: SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Invalid Pin Mode")); return; } } @@ -86,40 +87,18 @@ void GcodeSuite::M42() { #if HAS_FAN switch (pin) { - #if HAS_FAN0 - case FAN0_PIN: thermalManager.fan_speed[0] = pin_status; return; - #endif - #if HAS_FAN1 - case FAN1_PIN: thermalManager.fan_speed[1] = pin_status; return; - #endif - #if HAS_FAN2 - case FAN2_PIN: thermalManager.fan_speed[2] = pin_status; return; - #endif - #if HAS_FAN3 - case FAN3_PIN: thermalManager.fan_speed[3] = pin_status; return; - #endif - #if HAS_FAN4 - case FAN4_PIN: thermalManager.fan_speed[4] = pin_status; return; - #endif - #if HAS_FAN5 - case FAN5_PIN: thermalManager.fan_speed[5] = pin_status; return; - #endif - #if HAS_FAN6 - case FAN6_PIN: thermalManager.fan_speed[6] = pin_status; return; - #endif - #if HAS_FAN7 - case FAN7_PIN: thermalManager.fan_speed[7] = pin_status; return; - #endif + #define _CASE(N) case FAN##N##_PIN: thermalManager.fan_speed[N] = pin_status; return; + REPEAT(FAN_COUNT, _CASE) } #endif if (avoidWrite) { - SERIAL_ECHOLNPGM("?Cannot write to INPUT"); + SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Cannot write to INPUT")); return; } // An OUTPUT_OPEN_DRAIN should not be changed to normal OUTPUT (STM32) - // Use M42 Px M1/5 S0/1 to set the output type and then set value + // Use M42 Px T1/5 S0/1 to set the output type and then set value #ifndef OUTPUT_OPEN_DRAIN pinMode(pin, OUTPUT); #endif diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index e3ca43e17f..bf5549262d 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -115,7 +115,7 @@ else if (!parser.seen('W')) // if no S or W parameter, the DXC mode gets reset to the user's default dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; - #ifdef DEBUG_DXC_MODE + #if ENABLED(DEBUG_DXC_MODE) if (parser.seen('W')) { DEBUG_ECHO_START(); @@ -127,25 +127,24 @@ case DXC_MIRRORED_MODE: DEBUG_ECHOPGM("MIRRORED"); break; } DEBUG_ECHOPGM("\nActive Ext: ", active_extruder); - if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT "); - DEBUG_ECHOPGM(" parked."); - DEBUG_ECHOPGM("\nactive_extruder_x_pos: ", current_position.x); - DEBUG_ECHOPGM("\ninactive_extruder_x: ", inactive_extruder_x); - DEBUG_ECHOPGM("\nextruder_duplication_enabled: ", extruder_duplication_enabled); - DEBUG_ECHOPGM("\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset); - DEBUG_ECHOPGM("\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset); - DEBUG_ECHOPGM("\ndelayed_move_time: ", delayed_move_time); - DEBUG_ECHOPGM("\nX1 Home X: ", x_home_pos(0), "\nX1_MIN_POS=", X1_MIN_POS, "\nX1_MAX_POS=", X1_MAX_POS); - DEBUG_ECHOPGM("\nX2 Home X: ", x_home_pos(1), "\nX2_MIN_POS=", X2_MIN_POS, "\nX2_MAX_POS=", X2_MAX_POS); - DEBUG_ECHOPGM("\nX2_HOME_DIR=", X2_HOME_DIR, "\nX2_HOME_POS=", X2_HOME_POS); - DEBUG_ECHOPGM("\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE)); - DEBUG_ECHOPGM("\toolchange_settings.z_raise=", toolchange_settings.z_raise); - DEBUG_ECHOPGM("\nDEFAULT_DUPLICATION_X_OFFSET=", DEFAULT_DUPLICATION_X_OFFSET); - DEBUG_EOL(); + if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT ", F(" parked.")); + DEBUG_ECHOLNPGM( + "\nactive_extruder_x_pos: ", current_position.x, + "\ninactive_extruder_x: ", inactive_extruder_x, + "\nextruder_duplication_enabled: ", extruder_duplication_enabled, + "\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset, + "\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset, + "\ndelayed_move_time: ", delayed_move_time, + "\nX1 Home: ", x_home_pos(0), " X1_MIN_POS=", X1_MIN_POS, " X1_MAX_POS=", X1_MAX_POS, + "\nX2 Home: ", x_home_pos(1), " X2_MIN_POS=", X2_MIN_POS, " X2_MAX_POS=", X2_MAX_POS, + "\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE), + "\toolchange_settings.z_raise=", toolchange_settings.z_raise, + "\nDEFAULT_DUPLICATION_X_OFFSET=", DEFAULT_DUPLICATION_X_OFFSET + ); HOTEND_LOOP() { DEBUG_ECHOPGM_P(SP_T_STR, e); - LOOP_NUM_AXES(a) DEBUG_ECHOPGM(" hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]); + LOOP_NUM_AXES(a) DEBUG_ECHOPGM(" hotend_offset[", e, "].", C(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]); DEBUG_EOL(); } DEBUG_EOL(); @@ -156,26 +155,28 @@ #elif ENABLED(MULTI_NOZZLE_DUPLICATION) /** - * M605: Set multi-nozzle duplication mode + * M605: Multi Nozzle Mode * - * S2 - Enable duplication mode - * P[mask] - Bit-mask of nozzles to include in the duplication set. - * A value of 0 disables duplication. - * E[index] - Last nozzle index to include in the duplication set. - * A value of 0 disables duplication. + * Set multi-nozzle duplication mode. + * + * Parameters: + * S2 Enable duplication mode + * P Bit-mask of nozzles to include in the duplication set + * A value of 0 disables duplication + * E Last nozzle index to include in the duplication set + * A value of 0 disables duplication */ void GcodeSuite::M605() { bool ena = false; if (parser.seen("EPS")) { planner.synchronize(); if (parser.seenval('P')) duplication_e_mask = parser.value_int(); // Set the mask directly - else if (parser.seenval('E')) duplication_e_mask = pow(2, parser.value_int() + 1) - 1; // Set the mask by E index + else if (parser.seenval('E')) duplication_e_mask = _BV(parser.value_int() + 1) - 1; // Set the mask by E index ena = (2 == parser.intval('S', extruder_duplication_enabled ? 2 : 0)); set_duplication_enabled(ena && (duplication_e_mask >= 3)); } SERIAL_ECHO_START(); - SERIAL_ECHOPGM(STR_DUPLICATION_MODE); - serialprint_onoff(extruder_duplication_enabled); + SERIAL_ECHOPGM(STR_DUPLICATION_MODE, ON_OFF(extruder_duplication_enabled)); if (ena) { SERIAL_ECHOPGM(" ( "); HOTEND_LOOP() if (TEST(duplication_e_mask, e)) { SERIAL_ECHO(e); SERIAL_CHAR(' '); } diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp index ccde4f552c..837bb114b2 100644 --- a/Marlin/src/gcode/control/M7-M9.cpp +++ b/Marlin/src/gcode/control/M7-M9.cpp @@ -37,7 +37,7 @@ } #endif -#if EITHER(COOLANT_FLOOD, AIR_ASSIST) +#if ANY(COOLANT_FLOOD, AIR_ASSIST) #if ENABLED(AIR_ASSIST) #include "../../feature/spindle_laser.h" diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 90b25e7ed3..a7653a4037 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -34,7 +34,11 @@ #include "../../feature/power.h" #endif -#if HAS_SUICIDE +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../feature/powerloss.h" +#endif + +#if ANY(HAS_SUICIDE, CONFIGURABLE_MACHINE_NAME) #include "../../MarlinCore.h" #endif @@ -48,7 +52,7 @@ // S: Report the current power supply state and exit if (parser.seen('S')) { - SERIAL_ECHOF(powerManager.psu_on ? F("PS:1\n") : F("PS:0\n")); + SERIAL_ECHO(powerManager.psu_on ? F("PS:1\n") : F("PS:0\n")); return; } @@ -79,14 +83,20 @@ void GcodeSuite::M81() { print_job_timer.stop(); - #if BOTH(HAS_FAN, PROBING_FANS_OFF) + #if ALL(HAS_FAN, PROBING_FANS_OFF) thermalManager.fans_paused = false; ZERO(thermalManager.saved_fan_speed); #endif + TERN_(POWER_LOSS_RECOVERY, recovery.purge()); // Clear PLR on intentional shutdown + safe_delay(1000); // Wait 1 second before switching off - LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF "."); + #if ENABLED(CONFIGURABLE_MACHINE_NAME) + ui.set_status(&MString<30>(&marlin.machine_name, ' ', F(STR_OFF), '.')); + #else + LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF "."); + #endif bool delayed_power_off = false; @@ -112,9 +122,9 @@ void GcodeSuite::M81() { return; } - #if HAS_SUICIDE - suicide(); - #elif ENABLED(PSU_CONTROL) + #if ENABLED(PSU_CONTROL) powerManager.power_off_soon(); + #elif HAS_SUICIDE + marlin.suicide(); #endif } diff --git a/Marlin/src/gcode/control/M85.cpp b/Marlin/src/gcode/control/M85.cpp index ee868349ed..7846315413 100644 --- a/Marlin/src/gcode/control/M85.cpp +++ b/Marlin/src/gcode/control/M85.cpp @@ -32,11 +32,16 @@ void GcodeSuite::M85() { 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."); + SERIAL_ECHO_MSG(GCODE_ERR_MSG("M85 timeout must be > ", MS_TO_SEC(LASER_SAFETY_TIMEOUT_MS + 999), " s for laser safety.")); return; } #endif max_inactive_time = ms; } + else { + #if DISABLED(MARLIN_SMALL_BUILD) + SERIAL_ECHOLNPGM("Inactivity timeout ", MS_TO_SEC(max_inactive_time), " s."); + #endif + } } diff --git a/Marlin/src/gcode/control/M993_M994.cpp b/Marlin/src/gcode/control/M993_M994.cpp index 252792e522..392c37234e 100644 --- a/Marlin/src/gcode/control/M993_M994.cpp +++ b/Marlin/src/gcode/control/M993_M994.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ALL(HAS_SPI_FLASH, SDSUPPORT, MARLIN_DEV_MODE) +#if SPI_FLASH_BACKUP #include "../gcode.h" #include "../../sd/cardreader.h" @@ -49,7 +49,8 @@ void GcodeSuite::M993() { W25QXX.SPI_FLASH_BufferRead(buf, addr, COUNT(buf)); addr += COUNT(buf); card.write(buf, COUNT(buf)); - if (addr % (COUNT(buf) * 10) == 0) SERIAL_CHAR('.'); + if (!(addr % (COUNT(buf) * 10))) SERIAL_CHAR('.'); + if (!(addr % (COUNT(buf) * 32))) hal.watchdog_refresh(); } SERIAL_ECHOLNPGM(" done"); @@ -78,11 +79,12 @@ void GcodeSuite::M994() { card.read(buf, COUNT(buf)); W25QXX.SPI_FLASH_BufferWrite(buf, addr, COUNT(buf)); addr += COUNT(buf); - if (addr % (COUNT(buf) * 10) == 0) SERIAL_CHAR('.'); + if (!(addr % (COUNT(buf) * 10))) SERIAL_CHAR('.'); + if (!(addr % (COUNT(buf) * 32))) hal.watchdog_refresh(); } SERIAL_ECHOLNPGM(" done"); card.closefile(); } -#endif // HAS_SPI_FLASH && SDSUPPORT && MARLIN_DEV_MODE +#endif // SPI_FLASH_BACKUP diff --git a/Marlin/src/gcode/control/M997.cpp b/Marlin/src/gcode/control/M997.cpp index 74ed8b0d07..c651961902 100644 --- a/Marlin/src/gcode/control/M997.cpp +++ b/Marlin/src/gcode/control/M997.cpp @@ -24,8 +24,8 @@ #if ENABLED(PLATFORM_M997_SUPPORT) -#if ENABLED(DWIN_LCD_PROUI) - #include "../../lcd/e3v2/proui/dwin.h" +#if ENABLED(EXTENSIBLE_UI) + #include "../../lcd/extui/ui_api.h" #endif /** @@ -33,7 +33,7 @@ */ void GcodeSuite::M997() { - TERN_(DWIN_LCD_PROUI, DWIN_RebootScreen()); + TERN_(EXTENSIBLE_UI, ExtUI::onFirmwareFlash()); flashFirmware(parser.intval('S')); diff --git a/Marlin/src/gcode/control/M999.cpp b/Marlin/src/gcode/control/M999.cpp index b7d6db9f23..863ab8eb90 100644 --- a/Marlin/src/gcode/control/M999.cpp +++ b/Marlin/src/gcode/control/M999.cpp @@ -23,7 +23,7 @@ #include "../gcode.h" #include "../../lcd/marlinui.h" // for ui.reset_alert_level -#include "../../MarlinCore.h" // for marlin_state +#include "../../MarlinCore.h" // for setState #include "../queue.h" // for flush_and_request_resend /** @@ -36,7 +36,7 @@ * existing command buffer. */ void GcodeSuite::M999() { - marlin_state = MF_RUNNING; + marlin.setState(MF_RUNNING); ui.reset_alert_level(); if (parser.boolval('S')) return; diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp index 5e8f6b5436..d5affa37e2 100644 --- a/Marlin/src/gcode/control/T.cpp +++ b/Marlin/src/gcode/control/T.cpp @@ -20,14 +20,20 @@ * */ +#include "../../inc/MarlinConfigPre.h" + +#if HAS_TOOLCHANGE + #include "../gcode.h" #include "../../module/tool_change.h" -#if EITHER(HAS_MULTI_EXTRUDER, DEBUG_LEVELING_FEATURE) +#if ANY(HAS_MULTI_EXTRUDER, DEBUG_LEVELING_FEATURE) #include "../../module/motion.h" #endif -#if HAS_PRUSA_MMU2 +#if HAS_PRUSA_MMU3 + #include "../../feature/mmu3/mmu3.h" +#elif HAS_PRUSA_MMU2 #include "../../feature/mmu/mmu2.h" #endif @@ -37,24 +43,38 @@ /** * T0-T: Switch tool, usually switching extruders * - * F[units/min] Set the movement feedrate - * S1 Don't move the tool in XY after change + * Parameters: + * F Set the movement feedrate + * S1 Don't move the tool in XY after change * - * For PRUSA_MMU2(S) and EXTENDABLE_EMU_MMU2(S) - * T[n] Gcode to extrude at least 38.10 mm at feedrate 19.02 mm/s must follow immediately to load to extruder wheels. - * T? Gcode to extrude shouldn't have to follow. Load to extruder wheels is done automatically. - * Tx Same as T?, but nozzle doesn't have to be preheated. Tc requires a preheated nozzle to finish filament load. - * Tc Load to nozzle after filament was prepared by Tc and nozzle is already heated. + * For PRUSA_MMU2(S) and EXTENDABLE_EMU_MMU2(S) + * T G-code to extrude at least 38.10 mm at feedrate 19.02 mm/s must follow immediately to load to extruder wheels. + * T? G-code to extrude shouldn't have to follow. Load to extruder wheels is done automatically. + * Tx Same as T?, but nozzle doesn't have to be preheated. Tc requires a preheated nozzle to finish filament load. + * Tc Load to nozzle after filament was prepared by Tc and nozzle is already heated. */ void GcodeSuite::T(const int8_t tool_index) { + #if HAS_MULTI_EXTRUDER + // For 'T' with no parameter report the current tool. + if (parser.string_arg && *parser.string_arg == '*') { + SERIAL_ECHOLNPGM(STR_ACTIVE_EXTRUDER, active_extruder); + return; + } + #endif + DEBUG_SECTION(log_T, "T", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("...(", tool_index, ")"); // Count this command as movement / activity reset_stepper_timeout(); - #if HAS_PRUSA_MMU2 + #if HAS_PRUSA_MMU3 + if (parser.has_string()) { + mmu3.tool_change(parser.string_arg[0], uint8_t(tool_index)); // Special commands T?/Tx/Tc + return; + } + #elif HAS_PRUSA_MMU2 if (parser.string_arg) { mmu2.tool_change(parser.string_arg); // Special commands T?/Tx/Tc return; @@ -63,8 +83,10 @@ void GcodeSuite::T(const int8_t tool_index) { tool_change(tool_index #if HAS_MULTI_EXTRUDER - , TERN(PARKING_EXTRUDER, false, tool_index == active_extruder) // For PARKING_EXTRUDER motion is decided in tool_change() - || parser.boolval('S') + , parser.boolval('S') + || TERN(PARKING_EXTRUDER, false, tool_index == active_extruder) // For PARKING_EXTRUDER motion is decided in tool_change() #endif ); } + +#endif // HAS_TOOLCHANGE diff --git a/Marlin/src/gcode/eeprom/M500-M504.cpp b/Marlin/src/gcode/eeprom/M500-M504.cpp index 412d003355..ffa6d5c686 100644 --- a/Marlin/src/gcode/eeprom/M500-M504.cpp +++ b/Marlin/src/gcode/eeprom/M500-M504.cpp @@ -22,11 +22,10 @@ #include "../gcode.h" #include "../../module/settings.h" -#include "../../core/serial.h" #include "../../inc/MarlinConfig.h" #if ENABLED(CONFIGURATION_EMBEDDING) - #include "../../sd/SdBaseFile.h" + #include "../../sd/cardreader.h" #include "../../mczip.h" #endif @@ -66,11 +65,19 @@ void GcodeSuite::M502() { #if ENABLED(CONFIGURATION_EMBEDDING) if (parser.seen_test('C')) { - SdBaseFile file; - const uint16_t size = sizeof(mc_zip); + MediaFile file; // Need to create the config size on the SD card - if (file.open("mc.zip", O_WRITE|O_CREAT) && file.write(pgm_read_ptr(mc_zip), size) != -1 && file.close()) - SERIAL_ECHO_MSG("Configuration saved as 'mc.zip'"); + MediaFile root = card.getroot(); + if (file.open(&root, "mc.zip", O_WRITE|O_CREAT)) { + bool success = true; + for (uint16_t i = 0; success && i < sizeof(mc_zip); ++i) { + const uint8_t c = pgm_read_byte(&mc_zip[i]); + success = (file.write(c) == 1); + } + success = file.close() && success; + + if (success) SERIAL_ECHO_MSG("Configuration saved as 'mc.zip'"); + } } #endif } diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index db09faa883..7631cd0e8c 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -22,12 +22,13 @@ #include "../../../inc/MarlinConfig.h" -#if ENABLED(LIN_ADVANCE) +#if HAS_LIN_ADVANCE_K #include "../../gcode.h" #include "../../../module/planner.h" +#include "../../../module/stepper.h" -#if ENABLED(EXTRA_LIN_ADVANCE_K) +#if ENABLED(ADVANCE_K_EXTRA) float other_extruder_advance_K[EXTRUDERS]; uint8_t lin_adv_slot = 0; #endif @@ -35,9 +36,14 @@ /** * M900: Get or Set Linear Advance K-factor * T Which tool to address - * K Set current advance K factor (Slot 0). - * L Set secondary advance K factor (Slot 1). Requires EXTRA_LIN_ADVANCE_K. - * S<0/1> Activate slot 0 or 1. Requires EXTRA_LIN_ADVANCE_K. + * K Set current advance K factor (aka Slot 0). + * + * With ADVANCE_K_EXTRA: + * S<0/1> Activate slot 0 or 1. + * L Set secondary advance K factor (Slot 1). + * + * With SMOOTH_LIN_ADVANCE: + * U Set a tau value for LA smoothing */ void GcodeSuite::M900() { @@ -50,6 +56,7 @@ void GcodeSuite::M900() { #if EXTRUDERS < 2 constexpr uint8_t tool_index = 0; + UNUSED(tool_index); #else const uint8_t tool_index = parser.intval('T', active_extruder); if (tool_index >= EXTRUDERS) { @@ -58,38 +65,43 @@ void GcodeSuite::M900() { } #endif - float &kref = planner.extruder_advance_K[tool_index], newK = kref; - const float oldK = newK; + const float oldK = planner.get_advance_k(tool_index); + float newK = oldK; - #if ENABLED(EXTRA_LIN_ADVANCE_K) + #if ENABLED(SMOOTH_LIN_ADVANCE) + const float oldU = stepper.get_advance_tau(tool_index); + float newU = oldU; + #endif + + #if ENABLED(ADVANCE_K_EXTRA) float &lref = other_extruder_advance_K[tool_index]; - const bool old_slot = TEST(lin_adv_slot, tool_index), // The tool's current slot (0 or 1) - new_slot = parser.boolval('S', old_slot); // The passed slot (default = current) + const bool old_slot = TEST(lin_adv_slot, tool_index), // Each tool uses 1 bit to store its current slot (0 or 1) + new_slot = parser.boolval('S', old_slot); // The new slot (0 or 1) to set for the tool (default = no change) // If a new slot is being selected swap the current and // saved K values. Do here so K/L will apply correctly. if (new_slot != old_slot) { // Not the same slot? SET_BIT_TO(lin_adv_slot, tool_index, new_slot); // Update the slot for the tool - newK = lref; // Get new K value from backup - lref = oldK; // Save K to backup + newK = lref; // Get the backup K value (to apply below) + lref = oldK; // Back up the active K value } // Set the main K value. Apply if the main slot is active. if (parser.seenval('K')) { const float K = parser.value_float(); if (!WITHIN(K, 0, 10)) echo_value_oor('K'); - else if (new_slot) lref = K; // S1 Knn - else newK = K; // S0 Knn + else if (new_slot) lref = K; // S1 Knn (set main K in its backup slot) + else newK = K; // S0 Knn (use main K now) } // Set the extra K value. Apply if the extra slot is active. if (parser.seenval('L')) { const float L = parser.value_float(); if (!WITHIN(L, 0, 10)) echo_value_oor('L'); - else if (!new_slot) lref = L; // S0 Lnn - else newK = L; // S1 Lnn + else if (!new_slot) lref = L; // S0 Lnn (set extra K in its backup slot) + else newK = L; // S1 Lnn (use extra K now) } #else @@ -104,56 +116,82 @@ void GcodeSuite::M900() { #endif - if (newK != oldK) { + #if ENABLED(SMOOTH_LIN_ADVANCE) + if (parser.seenval('U')) { + const float tau = parser.value_float(); + if (WITHIN(tau, 0.0f, 0.5f)) + newU = tau; + else + echo_value_oor('U'); + } + #endif + + if (newK != oldK || TERN0(SMOOTH_LIN_ADVANCE, newU != oldU)) { planner.synchronize(); - kref = newK; + if (newK != oldK) planner.set_advance_k(newK, tool_index); + #if ENABLED(SMOOTH_LIN_ADVANCE) + if (newU != oldU) stepper.set_advance_tau(newU, tool_index); + #endif } if (!parser.seen_any()) { - #if ENABLED(EXTRA_LIN_ADVANCE_K) + #if ENABLED(ADVANCE_K_EXTRA) - #if EXTRUDERS < 2 - SERIAL_ECHOLNPGM("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")"); + #if DISABLED(DISTINCT_E_FACTORS) + SERIAL_ECHOLNPGM("Advance S", new_slot, " K", newK, "(S", !new_slot, " K", lref, ")"); #else EXTRUDER_LOOP() { const bool slot = TEST(lin_adv_slot, e); - SERIAL_ECHOLNPGM("Advance T", e, " S", slot, " K", planner.extruder_advance_K[e], - "(S", !slot, " K", other_extruder_advance_K[e], ")"); - SERIAL_EOL(); + SERIAL_ECHOLNPGM("Advance T", e, " S", slot, " K", planner.get_advance_k(e), + "(S", !slot, " K", other_extruder_advance_K[e], ")"); } #endif - #else + #else // !ADVANCE_K_EXTRA SERIAL_ECHO_START(); - #if EXTRUDERS < 2 - SERIAL_ECHOLNPGM("Advance K=", planner.extruder_advance_K[0]); + #if DISABLED(DISTINCT_E_FACTORS) + SERIAL_ECHOPGM("Advance K=", planner.get_advance_k()); + #if ENABLED(SMOOTH_LIN_ADVANCE) + SERIAL_ECHOPGM(" TAU=", stepper.get_advance_tau()); + #endif + SERIAL_EOL(); #else SERIAL_ECHOPGM("Advance K"); - EXTRUDER_LOOP() { - SERIAL_CHAR(' ', '0' + e, ':'); - SERIAL_DECIMAL(planner.extruder_advance_K[e]); - } + EXTRUDER_LOOP() SERIAL_ECHO(C(' '), C('0' + e), C(':'), planner.get_advance_k(e)); SERIAL_EOL(); + #if ENABLED(SMOOTH_LIN_ADVANCE) + SERIAL_ECHOPGM("Advance TAU"); + EXTRUDER_LOOP() SERIAL_ECHO(C(' '), C('0' + e), C(':'), stepper.get_advance_tau(e)); + SERIAL_EOL(); + #endif #endif - #endif + #endif // !ADVANCE_K_EXTRA } } void GcodeSuite::M900_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading(forReplay, F(STR_LINEAR_ADVANCE)); - #if EXTRUDERS < 2 + DISTINCT_E_LOOP() { report_echo_start(forReplay); - SERIAL_ECHOLNPGM(" M900 K", planner.extruder_advance_K[0]); - #else - EXTRUDER_LOOP() { - report_echo_start(forReplay); - SERIAL_ECHOLNPGM(" M900 T", e, " K", planner.extruder_advance_K[e]); - } - #endif + SERIAL_ECHOPGM( + #if ENABLED(DISTINCT_E_FACTORS) + " M900 T", e, " K" + #else + " M900 K" + #endif + ); + SERIAL_ECHO(planner.get_advance_k(e)); + #if ENABLED(SMOOTH_LIN_ADVANCE) + SERIAL_ECHOPGM(" U", stepper.get_advance_tau(e)); + #endif + SERIAL_EOL(); + } } -#endif // LIN_ADVANCE +#endif // HAS_LIN_ADVANCE_K diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index 19051ffd42..191a827ff4 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -31,10 +31,6 @@ millis_t chdk_timeout; // = 0 #endif -#if defined(PHOTO_POSITION) && PHOTO_DELAY_MS > 0 - #include "../../../MarlinCore.h" // for idle() -#endif - #ifdef PHOTO_RETRACT_MM #define _PHOTO_RETRACT_MM (PHOTO_RETRACT_MM + 0) @@ -47,7 +43,7 @@ #endif #ifdef PHOTO_RETRACT_MM - inline void e_move_m240(const float length, const_feedRate_t fr_mm_s) { + inline void e_move_m240(const float length, const feedRate_t fr_mm_s) { if (length && thermalManager.hotEnoughToExtrude(active_extruder)) unscaled_e_move(length, fr_mm_s); } @@ -84,7 +80,7 @@ inline void spin_photo_pin() { static constexpr uint32_t sequence[] = PHOTO_PULSES_US; - LOOP_L_N(i, COUNT(sequence)) + for (uint8_t i = 0; i < COUNT(sequence); ++i) pulse_photo_pin(sequence[i], !(i & 1)); } @@ -100,9 +96,9 @@ * M240: Trigger a camera by... * * - CHDK : Emulate a Canon RC-1 with a configurable ON duration. - * https://captain-slow.dk/2014/03/09/3d-printing-timelapses/ + * https://youtube.be/UqZ8Um5MZEA * - PHOTOGRAPH_PIN : Pulse a digital pin 16 times. - * See https://www.doc-diy.net/photo/rc-1_hacked/ + * See https://web.archive.org/web/20250327153953/www.doc-diy.net/photo/rc-1_hacked/ * - PHOTO_SWITCH_POSITION : Bump a physical switch with the X-carriage using a * configured position, delay, and retract length. * @@ -111,7 +107,7 @@ * B - Y offset to the return position * F - Override the XY movement feedrate * R - Retract/recover length (current units) - * S - Retract/recover feedrate (mm/m) + * S - Retract/recover feedrate (mm/min) * X - Move to X before triggering the shutter * Y - Move to Y before triggering the shutter * Z - Raise Z by a distance before triggering the shutter @@ -128,11 +124,13 @@ void GcodeSuite::M240() { if (homing_needed_error()) return; - const xyz_pos_t old_pos = { + const xyz_pos_t old_pos = NUM_AXIS_ARRAY( current_position.x + parser.linearval('A'), current_position.y + parser.linearval('B'), - current_position.z - }; + current_position.z, + current_position.i, current_position.j, current_position.k, + current_position.u, current_position.v, current_position.w + ); #ifdef PHOTO_RETRACT_MM const float rval = parser.linearval('R', _PHOTO_RETRACT_MM); @@ -140,7 +138,7 @@ void GcodeSuite::M240() { e_move_m240(-rval, sval); #endif - feedRate_t fr_mm_s = MMM_TO_MMS(parser.linearval('F')); + feedRate_t fr_mm_s = parser.feedrateval('F'); if (fr_mm_s) NOLESS(fr_mm_s, 10.0f); constexpr xyz_pos_t photo_position = PHOTO_POSITION; @@ -183,7 +181,7 @@ void GcodeSuite::M240() { #ifdef PHOTO_POSITION #if PHOTO_DELAY_MS > 0 const millis_t timeout = millis() + parser.intval('P', PHOTO_DELAY_MS); - while (PENDING(millis(), timeout)) idle(); + while (PENDING(millis(), timeout)) marlin.idle(); #endif do_blocking_move_to(old_pos, fr_mm_s); #ifdef PHOTO_RETRACT_MM diff --git a/Marlin/src/gcode/feature/cancel/M486.cpp b/Marlin/src/gcode/feature/cancel/M486.cpp index c1e90d1b96..237654e433 100644 --- a/Marlin/src/gcode/feature/cancel/M486.cpp +++ b/Marlin/src/gcode/feature/cancel/M486.cpp @@ -41,13 +41,13 @@ void GcodeSuite::M486() { if (parser.seen('T')) { cancelable.reset(); - cancelable.object_count = parser.intval('T', 1); + cancelable.state.object_count = parser.intval('T', 1); } if (parser.seenval('S')) cancelable.set_active_object(parser.value_int()); - if (parser.seen('C')) cancelable.cancel_active_object(); + if (parser.seen_test('C')) cancelable.cancel_active_object(); if (parser.seenval('P')) cancelable.cancel_object(parser.value_int()); diff --git a/Marlin/src/gcode/feature/clean/G12.cpp b/Marlin/src/gcode/feature/clean/G12.cpp index 0113170f1d..a5e312f8fd 100644 --- a/Marlin/src/gcode/feature/clean/G12.cpp +++ b/Marlin/src/gcode/feature/clean/G12.cpp @@ -57,10 +57,16 @@ void GcodeSuite::G12() { } #endif - const uint8_t pattern = parser.ushortval('P', 0), - strokes = parser.ushortval('S', NOZZLE_CLEAN_STROKES), - objects = parser.ushortval('T', NOZZLE_CLEAN_TRIANGLES); - const float radius = parser.linearval('R', NOZZLE_CLEAN_CIRCLE_RADIUS); + const uint8_t pattern = ( + #if COUNT_ENABLED(NOZZLE_CLEAN_PATTERN_LINE, NOZZLE_CLEAN_PATTERN_ZIGZAG, NOZZLE_CLEAN_PATTERN_CIRCLE) > 1 + parser.ushortval('P', NOZZLE_CLEAN_DEFAULT_PATTERN) + #else + NOZZLE_CLEAN_DEFAULT_PATTERN + #endif + ); + const uint8_t strokes = parser.ushortval('S', NOZZLE_CLEAN_STROKES), + objects = TERN0(NOZZLE_CLEAN_PATTERN_ZIGZAG, parser.ushortval('T', NOZZLE_CLEAN_TRIANGLES)); + const float radius = TERN0(NOZZLE_CLEAN_PATTERN_CIRCLE, parser.linearval('R', NOZZLE_CLEAN_CIRCLE_RADIUS)); const bool seenxyz = parser.seen("XYZ"); const uint8_t cleans = (!seenxyz || parser.boolval('X') ? _BV(X_AXIS) : 0) diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index b98d88845d..6bdfcd9b32 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -46,27 +46,27 @@ * M710 I127 A1 S255 D160 ; Set controller fan idle speed 50%, AutoMode On, Fan speed 100%, duration to 160 Secs */ void GcodeSuite::M710() { + if (!parser.seen("ADIRS")) return M710_report(); - const bool seenR = parser.seen('R'); - if (seenR) controllerFan.reset(); + if (parser.seen_test('R')) + controllerFan.reset(); - const bool seenS = parser.seenval('S'); - if (seenS) controllerFan.settings.active_speed = parser.value_byte(); + if (parser.seenval('S')) + controllerFan.settings.active_speed = parser.value_byte(); - const bool seenI = parser.seenval('I'); - if (seenI) controllerFan.settings.idle_speed = parser.value_byte(); + if (parser.seenval('I')) + controllerFan.settings.idle_speed = parser.value_byte(); - const bool seenA = parser.seenval('A'); - if (seenA) controllerFan.settings.auto_mode = parser.value_bool(); + if (parser.seenval('A')) + controllerFan.settings.auto_mode = parser.value_bool(); - const bool seenD = parser.seenval('D'); - if (seenD) controllerFan.settings.duration = parser.value_ushort(); - - if (!(seenR || seenS || seenI || seenA || seenD)) - M710_report(); + if (parser.seenval('D')) + controllerFan.settings.duration = parser.value_ushort(); } void GcodeSuite::M710_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_CONTROLLER_FAN)); SERIAL_ECHOLNPGM(" M710" " S", int(controllerFan.settings.active_speed), diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index 9ebe713cde..425d27a72d 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -46,15 +46,32 @@ * Set percentage of max current for all axes (Requires HAS_DIGIPOT_DAC) */ void GcodeSuite::M907() { + #if HAS_MOTOR_CURRENT_SPI 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()); - LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper.set_digipot_current(i, parser.value_int()); // X Y Z (I J K U V W) E (map to drivers according to DIGIPOT_CHANNELS. Default with NUM_AXES 3: map X Y Z E to X Y Z E0) - // Additional extruders use B,C. - // TODO: Change these parameters because 'E' is used and D should be reserved for debugging. B? + // S - Set current in mA for all axes + if (parser.seenval('S')) + for (uint8_t i = 0; i < MOTOR_CURRENT_COUNT; ++i) + stepper.set_digipot_current(i, parser.value_int()); + + // X Y Z I J K U V W E + // Map to drivers according to pots addresses. + // Default with NUM_AXES 3: map X Y Z E to X Y Z E0. + LOOP_LOGICAL_AXES(i) + if (parser.seenval(IAXIS_CHAR(i))) + stepper.set_digipot_current(i, parser.value_int()); + + /** + * Additional extruders use B,C in this legacy protocol + * TODO: Update to allow for an index with X, Y, Z, E axis to isolate a single stepper + * and use configured axis names instead of IJKUVW. i.e., Match the behavior of + * other G-codes that set stepper-specific parameters. If necessary deprecate G-codes. + * Bonus Points: Standardize a method that all G-codes can use to refer to one or + * more steppers/drivers and apply to various G-codes. + */ #if E_STEPPERS >= 2 if (parser.seenval('B')) stepper.set_digipot_current(E_AXIS + 1, parser.value_int()); #if E_STEPPERS >= 3 @@ -68,70 +85,106 @@ void GcodeSuite::M907() { #define HAS_X_Y_XY_I_J_K_U_V_W 1 #endif - #if HAS_X_Y_XY_I_J_K_U_V_W || ANY_PIN(MOTOR_CURRENT_PWM_E, MOTOR_CURRENT_PWM_Z) + #if ANY(HAS_X_Y_XY_I_J_K_U_V_W, HAS_MOTOR_CURRENT_PWM_E, HAS_MOTOR_CURRENT_PWM_Z) if (!parser.seen("S" #if HAS_X_Y_XY_I_J_K_U_V_W - "XY" SECONDARY_AXIS_GANG("I", "J", "K", "U", "V", "W") - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - "Z" - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - "E" + NUM_AXIS_GANG("X", "Y",, "I", "J", "K", "U", "V", "W") #endif + TERN_(HAS_MOTOR_CURRENT_PWM_Z, "Z") + TERN_(HAS_MOTOR_CURRENT_PWM_E, "E") )) return M907_report(); - if (parser.seenval('S')) LOOP_L_N(a, MOTOR_CURRENT_COUNT) stepper.set_digipot_current(a, parser.value_int()); + // S - Set all stepper current to the same value + if (parser.seenval('S')) { + const int16_t v = parser.value_int(); + for (uint8_t a = 0; a < MOTOR_CURRENT_COUNT; ++a) + stepper.set_digipot_current(a, v); + } - #if HAS_X_Y_XY_I_J_K_U_V_W - if (NUM_AXIS_GANG( - parser.seenval('X'), || parser.seenval('Y'), || false, - || parser.seenval('I'), || parser.seenval('J'), || parser.seenval('K'), - || parser.seenval('U'), || parser.seenval('V'), || parser.seenval('W') - )) stepper.set_digipot_current(0, parser.value_int()); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - if (parser.seenval('Z')) stepper.set_digipot_current(1, parser.value_int()); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - if (parser.seenval('E')) stepper.set_digipot_current(2, parser.value_int()); - #endif + // X Y I J K U V W - All aliases to set the current for "most axes." + // Only the value of the last given parameter is used. + if (ENABLED(HAS_X_Y_XY_I_J_K_U_V_W) && (NUM_AXIS_GANG( + parser.seenval('X'), || parser.seenval('Y'), || false, + || parser.seenval('I'), || parser.seenval('J'), || parser.seenval('K'), + || parser.seenval('U'), || parser.seenval('V'), || parser.seenval('W') + ))) + stepper.set_digipot_current(0, parser.value_int()); + + // Z - Set the current just for the Z axis + if (TERN0(HAS_MOTOR_CURRENT_PWM_Z, parser.seenval('Z'))) + stepper.set_digipot_current(1, parser.value_int()); + + // Z - Set the current just for the Extruder + if (TERN0(HAS_MOTOR_CURRENT_PWM_E, parser.seenval('E'))) + stepper.set_digipot_current(2, parser.value_int()); #endif #endif // HAS_MOTOR_CURRENT_PWM #if HAS_MOTOR_CURRENT_I2C - // this one uses actual amps in floating point - if (parser.seenval('S')) LOOP_L_N(q, DIGIPOT_I2C_NUM_CHANNELS) digipot_i2c.set_current(q, parser.value_float()); - LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) digipot_i2c.set_current(i, parser.value_float()); // X Y Z (I J K U V W) E (map to drivers according to pots adresses. Default with NUM_AXES 3 X Y Z E: map to X Y Z E0) + // This current driver takes actual Amps in floating point + // rather than milli-amps or some scalar unit. + + // S - Set the same current in Amps on all channels + if (parser.seenval('S')) { + const float v = parser.value_float(); + for (uint8_t q = 0; q < DIGIPOT_I2C_NUM_CHANNELS; ++q) + digipot_i2c.set_current(q, v); + } + + // X Y Z I J K U V W E + // Map to drivers according to pots addresses. + // Default with NUM_AXES 3: map X Y Z E to X Y Z E0. + LOOP_LOGICAL_AXES(i) + if (parser.seenval(IAXIS_CHAR(i))) + digipot_i2c.set_current(i, parser.value_float()); + // Additional extruders use B,C,D. - // TODO: Change these parameters because 'E' is used and because 'D' should be reserved for debugging. B? + // TODO: Make parameters work like other axis-specific / stepper-specific. See above. #if E_STEPPERS >= 2 for (uint8_t i = E_AXIS + 1; i < _MAX(DIGIPOT_I2C_NUM_CHANNELS, (NUM_AXES + 3)); i++) - if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float()); + if (parser.seenval('B' + i - (E_AXIS + 1))) + digipot_i2c.set_current(i, parser.value_float()); #endif - #endif + + #endif // HAS_MOTOR_CURRENT_I2C #if HAS_MOTOR_CURRENT_DAC + + // S - Set the same current percentage on all axes if (parser.seenval('S')) { const float dac_percent = parser.value_float(); - LOOP_LOGICAL_AXES(i) stepper_dac.set_current_percent(i, dac_percent); + LOOP_LOGICAL_AXES(i) + stepper_dac.set_current_percent(i, dac_percent); } - LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper_dac.set_current_percent(i, parser.value_float()); // X Y Z (I J K U V W) E (map to drivers according to DAC_STEPPER_ORDER. Default with NUM_AXES 3: X Y Z E map to X Y Z E0) + + // X Y Z I J K U V W E + // Map to drivers according to pots addresses. + // Default with NUM_AXES 3: map X Y Z E to X Y Z E0. + LOOP_LOGICAL_AXES(i) + if (parser.seenval(IAXIS_CHAR(i))) + stepper_dac.set_current_percent(i, parser.value_float()); + #endif } #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM void GcodeSuite::M907_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_STEPPER_MOTOR_CURRENTS)); #if HAS_MOTOR_CURRENT_PWM SERIAL_ECHOLNPGM_P( // PWM-based has 3 values: - PSTR(" M907 X"), stepper.motor_current_setting[0] // X, Y, (I, J, K, U, V, W) - , SP_Z_STR, stepper.motor_current_setting[1] // Z - , SP_E_STR, stepper.motor_current_setting[2] // E + PSTR(" M907 X"), stepper.motor_current_setting[0] // X, Y, (I, J, K, U, V, W) + #if HAS_MOTOR_CURRENT_PWM_Z + , SP_Z_STR, stepper.motor_current_setting[1] // Z + #endif + #if HAS_MOTOR_CURRENT_PWM_E + , SP_E_STR, stepper.motor_current_setting[2] // E + #endif ); #elif HAS_MOTOR_CURRENT_SPI SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values: diff --git a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp index ff174ecf13..5b906760ed 100644 --- a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp +++ b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp @@ -26,7 +26,6 @@ #include "../../../feature/filwidth.h" #include "../../../module/planner.h" -#include "../../../MarlinCore.h" #include "../../gcode.h" /** diff --git a/Marlin/src/gcode/feature/ft_motion/M493.cpp b/Marlin/src/gcode/feature/ft_motion/M493.cpp new file mode 100644 index 0000000000..272c3d7ab3 --- /dev/null +++ b/Marlin/src/gcode/feature/ft_motion/M493.cpp @@ -0,0 +1,503 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(FT_MOTION) + +#include "../../gcode.h" +#include "../../../module/ft_motion.h" +#include "../../../module/stepper.h" +#include "../../../lcd/marlinui.h" + +void say_shaper_type(const AxisEnum a, bool &sep, const char axis_name) { + if (sep) SERIAL_ECHOPGM(" ; "); + SERIAL_CHAR(axis_name, '='); + switch (ftMotion.cfg.shaper[a]) { + default: break; + TERN_(FTM_SHAPER_ZV, case ftMotionShaper_ZV: SERIAL_ECHOPGM("ZV"); break); + TERN_(FTM_SHAPER_ZVD, case ftMotionShaper_ZVD: SERIAL_ECHOPGM("ZVD"); break); + TERN_(FTM_SHAPER_ZVDD, case ftMotionShaper_ZVDD: SERIAL_ECHOPGM("ZVDD"); break); + TERN_(FTM_SHAPER_ZVDDD, case ftMotionShaper_ZVDDD: SERIAL_ECHOPGM("ZVDDD"); break); + TERN_(FTM_SHAPER_EI, case ftMotionShaper_EI: SERIAL_ECHOPGM("EI"); break); + TERN_(FTM_SHAPER_2HEI, case ftMotionShaper_2HEI: SERIAL_ECHOPGM("2 Hump EI"); break); + TERN_(FTM_SHAPER_3HEI, case ftMotionShaper_3HEI: SERIAL_ECHOPGM("3 Hump EI"); break); + TERN_(FTM_SHAPER_MZV, case ftMotionShaper_MZV: SERIAL_ECHOPGM("MZV"); break); + } + sep = true; +} + +void say_shaping() { + const ft_config_t &c = ftMotion.cfg; + + // FT Enabled + SERIAL_ECHO_TERNARY(c.active, "Fixed-Time Motion ", "en", "dis", "abled"); + + // FT Shaping + const bool is_shaping = AXIS_IS_SHAPING(X) || AXIS_IS_SHAPING(Y) || AXIS_IS_SHAPING(Z) || AXIS_IS_SHAPING(E); + bool sep = false; + if (is_shaping) { + #define STEPPER_E_NAME 'E' + #define _SAY_SHAPER(A) if (AXIS_IS_SHAPING(A)) say_shaper_type(_AXIS(A), sep, STEPPER_##A##_NAME); + SERIAL_ECHOPGM(" ("); + SHAPED_CODE(_SAY_SHAPER(A), _SAY_SHAPER(B), _SAY_SHAPER(C), _SAY_SHAPER(E)); + SERIAL_CHAR(')'); + } + SERIAL_EOL(); + + const bool z_based = TERN0(HAS_DYNAMIC_FREQ_MM, c.dynFreqMode == dynFreqMode_Z_BASED), + g_based = TERN0(HAS_DYNAMIC_FREQ_G, c.dynFreqMode == dynFreqMode_MASS_BASED), + dynamic = z_based || g_based; + + // FT Dynamic Frequency Mode + if (is_shaping) { + #if HAS_DYNAMIC_FREQ + SERIAL_ECHOPGM("Dynamic Frequency Mode "); + switch (c.dynFreqMode) { + default: + case dynFreqMode_DISABLED: SERIAL_ECHOPGM("disabled"); break; + #if HAS_DYNAMIC_FREQ_MM + case dynFreqMode_Z_BASED: SERIAL_ECHOPGM("Z-based"); break; + #endif + #if HAS_DYNAMIC_FREQ_G + case dynFreqMode_MASS_BASED: SERIAL_ECHOPGM("Mass-based"); break; + #endif + } + SERIAL_ECHOLNPGM("."); + #endif + + #if HAS_X_AXIS + SERIAL_CHAR(STEPPER_A_NAME); + SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: "); + SERIAL_ECHO(p_float_t(c.baseFreq.x, 2), F(" Hz")); + #if HAS_DYNAMIC_FREQ + if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.x, 2), F("Hz/"), z_based ? F("mm") : F("g")); + #endif + SERIAL_EOL(); + #endif + + #if HAS_Y_AXIS + SERIAL_CHAR(STEPPER_B_NAME); + SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: "); + SERIAL_ECHO(p_float_t(c.baseFreq.y, 2), F(" Hz")); + #if HAS_DYNAMIC_FREQ + if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.y, 2), F("Hz/"), z_based ? F("mm") : F("g")); + #endif + SERIAL_EOL(); + #endif + + #if ENABLED(FTM_SHAPER_Z) + SERIAL_CHAR(STEPPER_C_NAME); + SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: "); + SERIAL_ECHO(p_float_t(c.baseFreq.z, 2), F(" Hz")); + #if HAS_DYNAMIC_FREQ + if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.z, 2), F("Hz/"), z_based ? F("mm") : F("g")); + #endif + SERIAL_EOL(); + #endif + + #if ENABLED(FTM_SHAPER_E) + SERIAL_CHAR('E'); + SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: "); + SERIAL_ECHO(p_float_t(c.baseFreq.e, 2), F(" Hz")); + #if HAS_DYNAMIC_FREQ + if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.e, 2), F("Hz/"), z_based ? F("mm") : F("g")); + #endif + SERIAL_EOL(); + #endif + } +} + +void GcodeSuite::M493_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + + report_heading_etc(forReplay, F(STR_FT_MOTION)); + const ft_config_t &c = ftMotion.cfg; + + SERIAL_ECHOLNPGM( + " M493 S", c.active + #if HAS_DYNAMIC_FREQ + , " D", c.dynFreqMode + #endif + // Axis Synchronization + , " H", c.axis_sync_enabled + ); + + #if HAS_DYNAMIC_FREQ + #define F_REPORT(A) , F(" F"), c.dynFreqK.A + #else + #define F_REPORT(A) + #endif + #if HAS_FTM_EI_SHAPING + #define Q_REPORT(A) , F(" Q"), c.vtol.A + #else + #define Q_REPORT(A) + #endif + #define _REPORT_M493_AXIS(A) \ + SERIAL_ECHOLN(F(" M493 "), C(AXIS_CHAR(_AXIS(A))) \ + , F(" C"), c.shaper.A \ + , F(" A"), c.baseFreq.A \ + F_REPORT(A) \ + , F(" I"), c.zeta.A \ + Q_REPORT(A) \ + ); + // Shaper type for each axis + SHAPED_MAP(_REPORT_M493_AXIS); +} + +/** + * M493: Set Fixed-time Motion Control parameters + * + * S Set Fixed-Time motion mode on or off. Ignored with NO_STANDARD_MOTION. + * 0: Fixed-Time Motion OFF (Standard Motion) + * 1: Fixed-Time Motion ON + * + * V Flag to request version (Version 2+). (No reply = Version < 2) + * + * H Enable (1) or Disable (0) Axis Synchronization. + * + * Linear / Pressure Advance: + * + * P Enable (1) or Disable (0) Linear Advance pressure control + * + * Specifying Axes (for A,C,F,I,Q): + * + * X/Y/Z/E : Flag the axes (or core steppers) on which to apply the given parameters + * If none are given then XY is assumed. + * + * Compensator / Input Shaper: + * + * C Set Compensator Mode (Input Shaper) for the specified axes + * Users / slicers must remember to set the mode for all relevant axes! + * 0: NONE : No input shaper + * 1: ZV : Zero Vibration + * 2: ZVD : Zero Vibration and Derivative + * 3: ZVDD : Zero Vibration, Derivative, and Double Derivative + * 4: ZVDDD : Zero Vibration, Derivative, Double Derivative, and Triple Derivative + * 5: EI : Extra-Intensive + * 6: 2HEI : 2-Hump Extra-Intensive + * 7: 3HEI : 3-Hump Extra-Intensive + * 8: MZV : Mass-based Zero Vibration + * + * A Set static/base frequency for the specified axes + * I Set damping ratio for the specified axes + * Q Set vibration tolerance (vtol) for the specified axes + * + * Dynamic Frequency Mode: + * + * D Set Dynamic Frequency mode (for all axis compensators) + * 0: DISABLED + * 1: Z-based (Requires a Z axis) + * 2: Mass-based (Requires X and E axes) + * + * F Set frequency scaling for the specified axes + * + */ +void GcodeSuite::M493() { + // Request version of FTM. (No response = Version < 2) + if (parser.seen('V') && !parser.has_value()) { + SERIAL_ECHOLNPGM("FTM V" STRINGIFY(FTM_VERSION)); + return; + } + + struct { bool update:1, report:1; } flag = { false }; + + if (!parser.seen_any()) + flag.report = true; + + ft_config_t &c = ftMotion.cfg; + + #if HAS_STANDARD_MOTION + // Parse 'S' mode parameter. + if (parser.seen('S')) { + const bool active = parser.value_bool(); + if (active != c.active) { + ftMotion.toggle(); + flag.report = true; + } + } + #endif + + #if NUM_AXES_SHAPED > 0 + + const bool seenC = parser.seenval('C'); + const ftMotionShaper_t shaperVal = seenC ? (ftMotionShaper_t)parser.value_byte() : ftMotionShaper_NONE; + const bool goodShaper = WITHIN(shaperVal, ftMotionShaper_NONE, ftMotionShaper_MZV); + if (seenC && !goodShaper) { + SERIAL_ECHOLN(F("?Invalid "), F("(C)ompensator value. (0-"), int(ftMotionShaper_MZV)); + return; + } + auto set_shaper = [&](const AxisEnum axis, ftMotionShaper_t newsh) { + if (c.setShaper(axis, newsh)) + flag.update = flag.report = true; + }; + if (seenC) { + #define _SET_SHAPER(A) set_shaper(_AXIS(A), shaperVal); + SHAPED_MAP(_SET_SHAPER); + } + + #endif // NUM_AXES_SHAPED > 0 + + // Parse bool 'H' Axis Synchronization parameter. + if (parser.seen('H') && c.setAxisSync(parser.value_bool())) + flag.report = true; + + #if HAS_DYNAMIC_FREQ + + // Dynamic frequency mode parameter. + if (parser.seenval('D')) { + if (AXIS_IS_SHAPING(X) || AXIS_IS_SHAPING(Y) || AXIS_IS_SHAPING(Z) || AXIS_IS_SHAPING(E)) { + switch (c.setDynFreqMode(parser.value_byte())) { + case 0: break; // Same value, no update + case 1: flag.report = true; break; // New value, updated + default: SERIAL_ECHOLN(F("?Invalid "), F("(D)ynamic Frequency Mode value.")); break; + } + } + else + SERIAL_ECHOLNPGM("?Shaper required for (D)ynamic Frequency Mode ", c.dynFreqMode, "."); + } + + const bool modeUsesDynFreq = c.modeUsesDynFreq(); + + #endif // HAS_DYNAMIC_FREQ + + // Frequency parameter + const bool seenA = parser.seenval('A'); + const float baseFreqVal = seenA ? parser.value_float() : 0.0f; + const bool goodBaseFreq = seenA && c.goodBaseFreq(baseFreqVal); + if (seenA && !goodBaseFreq) + SERIAL_ECHOLN(F("?Invalid "), F("(A) Base Frequency value. ("), int(FTM_MIN_SHAPE_FREQ), C('-'), int((FTM_FS) / 2), C(')')); + + #if HAS_DYNAMIC_FREQ + // Dynamic Frequency parameter + const bool seenF = parser.seenval('F'); + const float baseDynFreqVal = seenF ? parser.value_float() : 0.0f; + if (seenF && !modeUsesDynFreq) + SERIAL_ECHOLNPGM("?Wrong mode for (F)requency scaling."); + #endif + + // Zeta parameter + const bool seenI = parser.seenval('I'); + const float zetaVal = seenI ? parser.value_float() : 0.0f; + const bool goodZeta = seenI && c.goodZeta(zetaVal); + if (seenI && !goodZeta) + SERIAL_ECHOLN(F("?Invalid "), F("(I) Zeta value. (0.01-" STRINGIFY(FTM_MAX_DAMPENING) ")")); // Zeta out of range + + #if HAS_FTM_EI_SHAPING + // Vibration Tolerance parameter + const bool seenQ = parser.seenval('Q'); + const float vtolVal = seenQ ? parser.value_float() : 0.0f; + const bool goodVtol = seenQ && c.goodVtol(vtolVal); + if (seenQ && !goodVtol) + SERIAL_ECHOLN(F("?Invalid "), F("(Q) Vibration Tolerance value. (0.0-1.0)")); // VTol out of range + #endif + + const bool apply_xy = !parser.seen("XYZE"); + + #if HAS_X_AXIS + + if (apply_xy || parser.seen_test('X')) { + + // Parse X frequency parameter + if (seenA) { + if (AXIS_IS_SHAPING(X)) { + // TODO: Frequency minimum is dependent on the shaper used; the above check isn't always correct. + if (goodBaseFreq && c.setBaseFreq(X_AXIS, baseFreqVal)) + flag.update = flag.report = true; + } + else // Mode doesn't use frequency. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (A) frequency."); + } + + #if HAS_DYNAMIC_FREQ + // Parse X frequency scaling parameter + if (seenF && c.setDynFreqK(X_AXIS, baseDynFreqVal)) + flag.report = true; + #endif + + // Parse X zeta parameter + if (seenI) { + if (AXIS_IS_SHAPING(X)) { + if (goodZeta && c.setZeta(X_AXIS, zetaVal)) + flag.update = true; + } + else + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (I) zeta parameter."); + } + + #if HAS_FTM_EI_SHAPING + // Parse X vtol parameter + if (seenQ) { + if (AXIS_IS_EISHAPING(X)) { + if (goodVtol && c.setVtol(X_AXIS, vtolVal)) + flag.update = true; + } + else + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (Q) vtol parameter."); + } + #endif + } + + #endif // HAS_X_AXIS + + #if HAS_Y_AXIS + + if (apply_xy || parser.seen_test('Y')) { + + // Parse Y frequency parameter + if (seenA) { + if (AXIS_IS_SHAPING(Y)) { + if (goodBaseFreq && c.setBaseFreq(Y_AXIS, baseFreqVal)) + flag.update = flag.report = true; + } + else // Mode doesn't use frequency. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (A) frequency."); + } + + #if HAS_DYNAMIC_FREQ + // Parse Y frequency scaling parameter + if (seenF && c.setDynFreqK(Y_AXIS, baseDynFreqVal)) + flag.report = true; + #endif + + // Parse Y zeta parameter + if (seenI) { + if (AXIS_IS_SHAPING(Y)) { + if (goodZeta && c.setZeta(Y_AXIS, zetaVal)) + flag.update = true; + } + else + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (I) zeta parameter."); + } + + #if HAS_FTM_EI_SHAPING + // Parse Y vtol parameter + if (seenQ) { + if (AXIS_IS_EISHAPING(Y)) { + if (goodVtol && c.setVtol(Y_AXIS, vtolVal)) + flag.update = true; + } + else + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (Q) vtol parameter."); + } + #endif + } + + #endif // HAS_Y_AXIS + + #if ENABLED(FTM_SHAPER_Z) + + if (parser.seen_test('Z')) { + + // Parse Z frequency parameter + if (seenA) { + if (AXIS_IS_SHAPING(Z)) { + if (goodBaseFreq && c.setBaseFreq(Z_AXIS, baseFreqVal)) + flag.update = flag.report = true; + } + else // Mode doesn't use frequency. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (A) frequency."); + } + + #if HAS_DYNAMIC_FREQ + // Parse Z frequency scaling parameter + if (seenF && c.setDynFreqK(Z_AXIS, baseDynFreqVal)) + flag.report = true; + #endif + + // Parse Z zeta parameter + if (seenI) { + if (AXIS_IS_SHAPING(Z)) { + if (goodZeta && c.setZeta(Z_AXIS, zetaVal)) + flag.update = true; + } + else + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (I) zeta parameter."); + } + + #if HAS_FTM_EI_SHAPING + // Parse Z vtol parameter + if (seenQ) { + if (AXIS_IS_EISHAPING(Z)) { + if (goodVtol && c.setVtol(Z_AXIS, vtolVal)) + flag.update = true; + } + else + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (Q) vtol parameter."); + } + #endif + } + + #endif // FTM_SHAPER_Z + + #if ENABLED(FTM_SHAPER_E) + + if (parser.seen_test('E')) { + + // Parse E frequency parameter + if (seenA) { + if (AXIS_IS_SHAPING(E)) { + if (goodBaseFreq && c.setBaseFreq(E_AXIS, baseFreqVal)) + flag.update = flag.report = true; + } + else // Mode doesn't use frequency. + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (A) frequency."); + } + + #if HAS_DYNAMIC_FREQ + // Parse E frequency scaling parameter + if (seenF && c.setDynFreqK(E_AXIS, baseDynFreqVal)) + flag.report = true; + #endif + + // Parse E zeta parameter + if (seenI) { + if (AXIS_IS_SHAPING(E)) { + if (goodZeta && c.setZeta(E_AXIS, zetaVal)) + flag.update = true; + } + else + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (I) zeta parameter."); + } + + #if HAS_FTM_EI_SHAPING + // Parse E vtol parameter + if (seenQ) { + if (AXIS_IS_EISHAPING(E)) { + if (goodVtol && c.setVtol(E_AXIS, vtolVal)) + flag.update = true; + } + else + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (Q) vtol parameter."); + } + #endif + } + + #endif // FTM_SHAPER_E + + if (flag.update || flag.report) + ui.refresh(); + + if (flag.report) say_shaping(); +} + +#endif // FT_MOTION diff --git a/Marlin/src/gcode/feature/ft_motion/M494.cpp b/Marlin/src/gcode/feature/ft_motion/M494.cpp new file mode 100644 index 0000000000..d6161a9574 --- /dev/null +++ b/Marlin/src/gcode/feature/ft_motion/M494.cpp @@ -0,0 +1,139 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(FT_MOTION) + +#include "../../gcode.h" +#include "../../../module/ft_motion.h" +#include "../../../module/stepper.h" +#include "../../../module/planner.h" +#include "../../../lcd/marlinui.h" + +void say_ftm_settings() { + #if ANY(FTM_POLYS, FTM_SMOOTHING) + const ft_config_t &c = ftMotion.cfg; + #endif + + #if ENABLED(FTM_POLYS) + SERIAL_ECHOLN(F(" Trajectory: "), ftMotion.getTrajectoryName(), C('('), (uint8_t)ftMotion.getTrajectoryType(), C(')')); + if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) + SERIAL_ECHOLNPGM(" Poly6 Overshoot: ", p_float_t(c.poly6_acceleration_overshoot, 3)); + #endif + + #if ENABLED(FTM_SMOOTHING) + #define _SMOO_REPORT(A) SERIAL_ECHOLN(F(" "), C(IAXIS_CHAR(_AXIS(A))), F(" smoothing time: "), p_float_t(c.smoothingTime.A, 3), C('s')); + CARTES_MAP(_SMOO_REPORT); + #endif +} + +void GcodeSuite::M494_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + + report_heading_etc(forReplay, F("FT Motion")); + SERIAL_ECHOPGM(" M494 T", (uint8_t)ftMotion.getTrajectoryType()); + + #if ANY(FTM_POLYS, FTM_SMOOTHING) + const ft_config_t &c = ftMotion.cfg; + #endif + + #if ENABLED(FTM_SMOOTHING) + SERIAL_ECHOPGM(CARTES_PAIRED_LIST( + " X", c.smoothingTime.X, + " Y", c.smoothingTime.Y, + " Z", c.smoothingTime.Z, + " E", c.smoothingTime.E + )); + #endif + + #if ENABLED(FTM_POLYS) + if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) + SERIAL_ECHOPGM(" O", c.poly6_acceleration_overshoot); + #endif + + SERIAL_EOL(); +} + +/** + * M494: Set Fixed-time Motion Control parameters + * + * Parameters: + * T Set trajectory generator type (0=TRAPEZOIDAL, 1=POLY5, 2=POLY6) + * O Set acceleration overshoot for POLY6 (1.25-1.875) + * X