diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md
new file mode 100644
index 000000000000..48beca2c2d18
--- /dev/null
+++ b/.github/ISSUE_TEMPLATE/bug_report.md
@@ -0,0 +1,43 @@
+---
+name: Bug report
+about: Report a bug in Marlin
+title: "[BUG] (short description)"
+labels: ''
+assignees: ''
+
+---
+
+
+
+### Bug Description
+
+
+
+### My Configurations
+
+**Required:** Please include a ZIP file containing your `Configuration.h` and `Configuration_adv.h` files.
+
+### Steps to Reproduce
+
+
+
+1. [First Step]
+2. [Second Step]
+3. [and so on...]
+
+**Expected behavior:** [What you expect to happen]
+
+**Actual behavior:** [What actually happens]
+
+#### Additional Information
+
+* Provide pictures or links to videos that clearly demonstrate the issue.
+* See [How Can I Contribute](#how-can-i-contribute) for additional guidelines.
diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml
new file mode 100644
index 000000000000..4b283d26005c
--- /dev/null
+++ b/.github/ISSUE_TEMPLATE/config.yml
@@ -0,0 +1,17 @@
+blank_issues_enabled: false
+contact_links:
+ - name: Marlin Documentation
+ url: http://marlinfw.org/
+ about: Lots of documentation on installing and using Marlin.
+ - name: MarlinFirmware Facebook group
+ url: https://www.facebook.com/groups/1049718498464482
+ about: Please ask and answer questions here.
+ - name: Marlin on Discord
+ url: https://discord.gg/n5NJ59y
+ about: Join the Discord server for support and discussion.
+ - name: Marlin Discussion Forum
+ url: http://forums.reprap.org/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!
diff --git a/.github/ISSUE_TEMPLATE/feature_request.md b/.github/ISSUE_TEMPLATE/feature_request.md
new file mode 100644
index 000000000000..24de8d01419b
--- /dev/null
+++ b/.github/ISSUE_TEMPLATE/feature_request.md
@@ -0,0 +1,35 @@
+---
+name: Feature request
+about: Request a Feature
+title: "[FR] (feature request title)"
+labels: 'T: Feature Request'
+assignees: ''
+
+---
+
+
+
+### Description
+
+
+
+### Feature Workflow
+
+
+
+1. [First Action]
+2. [Second Action]
+3. [and so on...]
+
+#### Additional Information
+
+* Provide pictures or links that demonstrate a similar feature or concept.
+* See [How Can I Contribute](#how-can-i-contribute) for additional guidelines.
diff --git a/.github/issue_template.md b/.github/issue_template.md
index 6cb34b8f588a..a211ca5e2715 100644
--- a/.github/issue_template.md
+++ b/.github/issue_template.md
@@ -1,35 +1,11 @@
-
-
-### Description
-
-
-
-### Steps to Reproduce
-
-
-
-1. [First Step]
-2. [Second Step]
-3. [and so on...]
-
-**Expected behavior:** [What you expect to happen]
-
-**Actual behavior:** [What actually happens]
-
-#### Additional Information
-
-* Include a ZIP file containing your `Configuration.h` and `Configuration_adv.h` files.
-* Provide pictures or links to videos that clearly demonstrate the issue.
-* See [How Can I Contribute](#how-can-i-contribute) for additional guidelines.
diff --git a/.github/workflows/bump-date.yml b/.github/workflows/bump-date.yml
new file mode 100644
index 000000000000..54902da8c908
--- /dev/null
+++ b/.github/workflows/bump-date.yml
@@ -0,0 +1,35 @@
+#
+# bump-date.yml
+# Bump the distribution date once per day
+#
+
+name: Bump Distribution Date
+
+on:
+ schedule:
+ - cron: '0 0 * * *'
+
+jobs:
+ bump_date:
+ name: Bump Distribution Date
+ if: github.repository == 'MarlinFirmware/Marlin'
+
+ runs-on: ubuntu-latest
+
+ steps:
+
+ - name: Check out bugfix-2.0.x
+ uses: actions/checkout@v2
+ with:
+ ref: bugfix-2.0.x
+
+ - name: Bump Distribution Date
+ run: |
+ # Inline Bump Script
+ DIST=$( date +"%Y-%m-%d" )
+ eval "sed -E -i 's/(#define +STRING_DISTRIBUTION_DATE) .*$/\1 \"$DIST\"/g' Marlin/src/inc/Version.h" && \
+ 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
diff --git a/.github/workflows/check-pr.yml b/.github/workflows/check-pr.yml
new file mode 100644
index 000000000000..aa4a2c59c9a4
--- /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:
+ 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-latest
+
+ steps:
+ - uses: peter-evans/close-pull@v1
+ with:
+ delete-branch: false
+ comment: >
+ Thanks for your contribution! Unfortunately we can't accept PRs directed at release branches. We make patches to the bugfix branches and only later do we push them out as releases.
+
+ Please redo this PR starting with the `bugfix-2.0.x` branch and be careful to target `bugfix-2.0.x` when resubmitting the PR.
+
+ It may help to set your fork's default branch to `bugfix-2.0.x`.
+
+ See [this page](http://marlinfw.org/docs/development/getting_started_pull_requests.html) for full instructions.
diff --git a/.github/workflows/close-stale.yml b/.github/workflows/close-stale.yml
new file mode 100644
index 000000000000..89d5d65351d9
--- /dev/null
+++ b/.github/workflows/close-stale.yml
@@ -0,0 +1,27 @@
+#
+# close-stale.yml
+# Close open issues after a period of inactivity
+#
+
+name: Close Stale Issues
+
+on:
+ schedule:
+ - cron: "22 1 * * *"
+
+jobs:
+ stale:
+ name: Close Stale Issues
+ if: github.repository == 'MarlinFirmware/Marlin'
+
+ runs-on: ubuntu-latest
+
+ steps:
+ - uses: actions/stale@v3
+ with:
+ repo-token: ${{ secrets.GITHUB_TOKEN }}
+ stale-issue-message: 'This issue has had no activity in the last 30 days. Please add a reply if you want to keep this issue active, otherwise it will be automatically closed within 7 days.'
+ days-before-stale: 30
+ days-before-close: 7
+ stale-issue-label: 'stale-closing-soon'
+ exempt-issue-labels: 'T: Feature Request'
diff --git a/.github/workflows/lock-closed.yml b/.github/workflows/lock-closed.yml
new file mode 100644
index 000000000000..8cdcd7a8369e
--- /dev/null
+++ b/.github/workflows/lock-closed.yml
@@ -0,0 +1,32 @@
+#
+# lock-closed.yml
+# Lock closed issues after a period of inactivity
+#
+
+name: Lock Closed Issues
+
+on:
+ schedule:
+ - cron: '0 1/13 * * *'
+
+jobs:
+ lock:
+ name: Lock Closed Issues
+ if: github.repository == 'MarlinFirmware/Marlin'
+
+ runs-on: ubuntu-latest
+
+ steps:
+ - uses: dessant/lock-threads@v2
+ with:
+ github-token: ${{ github.token }}
+ process-only: 'issues'
+ issue-lock-inactive-days: '60'
+ issue-exclude-created-before: ''
+ issue-exclude-labels: 'no-locking'
+ issue-lock-labels: ''
+ issue-lock-comment: >
+ This issue has been automatically locked since there
+ has not been any recent activity after it was closed.
+ Please open a new issue for related bugs.
+ issue-lock-reason: ''
diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml
index 35cd920adff8..b2287837998b 100644
--- a/.github/workflows/test-builds.yml
+++ b/.github/workflows/test-builds.yml
@@ -41,6 +41,7 @@ jobs:
- mega2560
- teensy31
- teensy35
+ - teensy41
- SAMD51_grandcentral_m4
# Extended AVR Environments
diff --git a/.github/workflows/unlock-reopened.yml b/.github/workflows/unlock-reopened.yml
new file mode 100644
index 000000000000..614ef3fab297
--- /dev/null
+++ b/.github/workflows/unlock-reopened.yml
@@ -0,0 +1,22 @@
+#
+# unlock-reopened.yml
+# Unlock an issue whenever it is re-opened
+#
+
+name: "Unlock reopened issue"
+
+on:
+ issues:
+ types: [reopened]
+
+jobs:
+ unlock:
+ name: Unlock Reopened
+ if: github.repository == 'MarlinFirmware/Marlin'
+
+ runs-on: ubuntu-latest
+
+ steps:
+ - uses: OSDKDev/unlock-issues@v1.1
+ with:
+ repo-token: "${{ secrets.GITHUB_TOKEN }}"
diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h
index 9c8ae93a90e1..628cd28aad85 100644
--- a/Marlin/Configuration.h
+++ b/Marlin/Configuration.h
@@ -36,9 +36,8 @@
* - Extra features
*
* Advanced settings can be found in Configuration_adv.h
- *
*/
-#define CONFIGURATION_H_VERSION 020006
+#define CONFIGURATION_H_VERSION 020007
//===========================================================================
//============================= Getting Started =============================
@@ -349,11 +348,10 @@
#endif
#endif
-// @section temperature
-
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
+// @section temperature
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
@@ -392,6 +390,7 @@
* 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v excitation (STM32 \ LPC176x....)
* 22 : 100k (hotend) with 4.7k pullup to 3.3V and 220R to analog input (as in GTM32 Pro vB)
* 23 : 100k (bed) with 4.7k pullup to 3.3v and 220R to analog input (as in GTM32 Pro vB)
+ * 30 : Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K / B3950 (4.7k pullup)
* 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 61 : 100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup
@@ -489,23 +488,17 @@
//#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders)
// Set/get with gcode: M301 E[extruder number, 0-2]
- // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
-
- // Ultimaker
- #define DEFAULT_Kp 19.4
- #define DEFAULT_Ki 1.96
- #define DEFAULT_Kd 48.3
-
- // MakerGear
- //#define DEFAULT_Kp 7.0
- //#define DEFAULT_Ki 0.1
- //#define DEFAULT_Kd 12
-
- // Mendel Parts V9 on 12V
- //#define DEFAULT_Kp 63.0
- //#define DEFAULT_Ki 2.25
- //#define DEFAULT_Kd 440
-
+ #if ENABLED(PID_PARAMS_PER_HOTEND)
+ // Specify between 1 and HOTENDS values per array.
+ // If fewer than EXTRUDER values are provided, the last element will be repeated.
+ #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 19.4
+ #define DEFAULT_Ki 1.96
+ #define DEFAULT_Kd 48.3
+ #endif
#endif // PIDTEMP
//===========================================================================
@@ -541,18 +534,12 @@
//#define MIN_BED_POWER 0
//#define PID_BED_DEBUG // Sends debug data to the serial port.
- //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)
+ // 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
- //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
- //from pidautotune
- //#define DEFAULT_bedKp 97.1
- //#define DEFAULT_bedKi 1.41
- //#define DEFAULT_bedKd 1675.16
-
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
@@ -871,7 +858,6 @@
* - For simple switches connect...
* - normally-closed switches to GND and D32.
* - normally-open switches to 5V and D32.
- *
*/
//#define Z_MIN_PROBE_PIN 32 // Pin 32 is the RAMPS default
@@ -1588,7 +1574,6 @@
*
* Caveats: The ending Z should be the same as starting Z.
* Attention: EXPERIMENTAL. G-code arguments may change.
- *
*/
//#define NOZZLE_CLEAN_FEATURE
@@ -1741,7 +1726,6 @@
*
* 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
@@ -1978,6 +1962,14 @@
//
//#define FF_INTERFACEBOARD
+//
+// TFT GLCD Panel with Marlin UI
+// Panel connected to main board by SPI or I2C interface.
+// See https://github.com/Serhiy-K/TFTGLCDAdapter
+//
+//#define TFTGLCD_PANEL_SPI
+//#define TFTGLCD_PANEL_I2C
+
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
@@ -2174,6 +2166,9 @@
// Touch-screen LCD for Malyan M200/M300 printers
//
//#define MALYAN_LCD
+#if ENABLED(MALYAN_LCD)
+ #define LCD_SERIAL_PORT 1 // Default is 1 for Malyan M200
+#endif
//
// Touch UI for FTDI EVE (FT800/FT810) displays
@@ -2181,6 +2176,16 @@
//
//#define TOUCH_UI_FTDI_EVE
+//
+// Touch-screen LCD for Anycubic printers
+//
+//#define ANYCUBIC_LCD_I3MEGA
+//#define ANYCUBIC_LCD_CHIRON
+#if EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON)
+ #define LCD_SERIAL_PORT 3 // Default is 3 for Anycubic
+ //#define ANYCUBIC_LCD_DEBUG
+#endif
+
//
// Third-party or vendor-customized controller interfaces.
// Sources should be installed in 'src/lcd/extensible_ui'.
@@ -2317,9 +2322,6 @@
// then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis)
//#define TEMP_STAT_LEDS
-// SkeinForge sends the wrong arc G-codes when using Arc Point as fillet procedure
-//#define SF_ARC_FIX
-
// Support for the BariCUDA Paste Extruder
//#define BARICUDA
@@ -2352,7 +2354,6 @@
* *** CAUTION ***
*
* LED Type. Enable only one of the following two options.
- *
*/
//#define RGB_LED
//#define RGBW_LED
@@ -2406,17 +2407,12 @@
#define PRINTER_EVENT_LEDS
#endif
-/**
- * R/C SERVO support
- * Sponsored by TrinityLabs, Reworked by codexmas
- */
-
/**
* Number of servos
*
* For some servo-related options NUM_SERVOS will be set automatically.
* Set this manually if there are extra servos needing manual control.
- * Leave undefined or set to 0 to entirely disable the servo subsystem.
+ * Set to 0 to turn off servo support.
*/
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
@@ -2428,5 +2424,5 @@
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
-// Allow servo angle to be edited and saved to EEPROM
-//#define EDITABLE_SERVO_ANGLES
\ No newline at end of file
+// Edit servo angles with M281 and save to EEPROM with M500
+//#define EDITABLE_SERVO_ANGLES
diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h
index 74977750dc83..9a5ac1edd793 100644
--- a/Marlin/Configuration_adv.h
+++ b/Marlin/Configuration_adv.h
@@ -31,15 +31,13 @@
* Some of these settings can damage your printer if improperly set!
*
* Basic settings can be found in Configuration.h
- *
*/
-#define CONFIGURATION_ADV_H_VERSION 020006
-
-// @section temperature
+#define CONFIGURATION_ADV_H_VERSION 020007
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
+// @section temperature
/**
* Thermocouple sensors are quite sensitive to noise. Any noise induced in
@@ -128,9 +126,19 @@
#define HEATER_BED_INVERTING true
#endif
-/**
- * Heated Chamber settings
- */
+//
+// Heated Bed Bang-Bang options
+//
+#if DISABLED(PIDTEMPBED)
+ #define BED_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control
+ #if ENABLED(BED_LIMIT_SWITCHING)
+ #define BED_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > BED_HYSTERESIS
+ #endif
+#endif
+
+//
+// Heated Chamber options
+//
#if TEMP_SENSOR_CHAMBER
#define CHAMBER_MINTEMP 5
#define CHAMBER_MAXTEMP 60
@@ -138,12 +146,28 @@
//#define CHAMBER_LIMIT_SWITCHING
//#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
//#define HEATER_CHAMBER_INVERTING false
-#endif
-#if DISABLED(PIDTEMPBED)
- #define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
- #if ENABLED(BED_LIMIT_SWITCHING)
- #define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
+ //#define CHAMBER_FAN // Enable a fan on the chamber
+ #if ENABLED(CHAMBER_FAN)
+ #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve.
+ #if CHAMBER_FAN_MODE == 0
+ #define CHAMBER_FAN_BASE 255 // Chamber fan PWM (0-255)
+ #elif CHAMBER_FAN_MODE == 1
+ #define CHAMBER_FAN_BASE 128 // Base chamber fan PWM (0-255); turns on when chamber temperature is above the target
+ #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C above target
+ #elif CHAMBER_FAN_MODE == 2
+ #define CHAMBER_FAN_BASE 128 // Minimum chamber fan PWM (0-255)
+ #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C difference from target
+ #endif
+ #endif
+
+ //#define CHAMBER_VENT // Enable a servo-controlled vent on the chamber
+ #if ENABLED(CHAMBER_VENT)
+ #define CHAMBER_VENT_SERVO_NR 1 // Index of the vent servo
+ #define HIGH_EXCESS_HEAT_LIMIT 5 // How much above target temp to consider there is excess heat in the chamber
+ #define LOW_EXCESS_HEAT_LIMIT 3
+ #define MIN_COOLING_SLOPE_TIME_CHAMBER_VENT 20
+ #define MIN_COOLING_SLOPE_DEG_CHAMBER_VENT 1.5
#endif
#endif
@@ -740,7 +764,6 @@
* | 4 3 | 1 4 | 2 1 | 3 2 |
* | | | | |
* | 1 2 | 2 3 | 3 4 | 4 1 |
- *
*/
#ifndef Z_STEPPER_ALIGN_XY
//#define Z_STEPPERS_ORIENTATION 0
@@ -788,6 +811,9 @@
// Enable to restore leveling setup after operation
#define RESTORE_LEVELING_AFTER_G35
+ // Add a menu item for Assisted Tramming
+ //#define ASSISTED_TRAMMING_MENU_ITEM
+
/**
* Screw thread:
* M3: 30 = Clockwise, 31 = Counter-Clockwise
@@ -1049,6 +1075,14 @@
#if HAS_LCD_MENU
+ // Add Probe Z Offset calibration to the Z Probe Offsets menu
+ #if HAS_BED_PROBE
+ //#define PROBE_OFFSET_WIZARD
+ #if ENABLED(PROBE_OFFSET_WIZARD)
+ #define PROBE_OFFSET_START -4.0 // Estimated nozzle-to-probe Z offset, plus a little extra
+ #endif
+ #endif
+
// Include a page of printer information in the LCD Main Menu
#define LCD_INFO_MENU
#if ENABLED(LCD_INFO_MENU)
@@ -1105,23 +1139,26 @@
#define BOOTSCREEN_TIMEOUT 2000 // (ms) Total Duration to display the boot screen(s)
#endif
-#if HAS_GRAPHICAL_LCD && EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY)
- //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits
- #define SHOW_REMAINING_TIME // Display estimated time to completion
+#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) && ANY(HAS_MARLINUI_U8GLIB, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL)
+ #define SHOW_REMAINING_TIME // Display estimated time to completion
#if ENABLED(SHOW_REMAINING_TIME)
- //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation
- //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time
+ //#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
+
+ #if HAS_MARLINUI_U8GLIB
+ //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits
#endif
-#endif
-#if HAS_CHARACTER_LCD && EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY)
- //#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_ONCE // Show the message for MSG_TIME then clear it
- //#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
+ #if EITHER(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_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
@@ -1164,6 +1201,7 @@
#if ENABLED(POWER_LOSS_RECOVERY)
#define PLR_ENABLED_DEFAULT false // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500)
//#define BACKUP_POWER_SUPPLY // Backup power / UPS to move the steppers on power loss
+ //#define POWER_LOSS_RECOVER_ZHOME // Z homing is needed for proper recovery. 99.9% of the time this should be disabled!
//#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module.
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
@@ -1324,7 +1362,7 @@
* controller events, as there is a trade-off between reliable
* printing performance versus fast display updates.
*/
-#if HAS_GRAPHICAL_LCD
+#if HAS_MARLINUI_U8GLIB
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
@@ -1339,7 +1377,7 @@
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
- // A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
+ // A smaller font may be used on the Info Screen. Costs 2434 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
@@ -1394,18 +1432,18 @@
//#define MARLIN_SNAKE
//#define GAMES_EASTER_EGG // Add extra blank lines above the "Games" sub-menu
-#endif // HAS_GRAPHICAL_LCD
+#endif // HAS_MARLINUI_U8GLIB
//
// Additional options for DGUS / DWIN displays
//
#if HAS_DGUS_LCD
- #define DGUS_SERIAL_PORT 3
- #define DGUS_BAUDRATE 115200
+ #define LCD_SERIAL_PORT 3
+ #define LCD_BAUDRATE 115200
#define DGUS_RX_BUFFER_SIZE 128
#define DGUS_TX_BUFFER_SIZE 48
- //#define DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR)
+ //#define SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR)
#define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates
@@ -1572,6 +1610,7 @@
#if ENABLED(BABYSTEPPING)
//#define INTEGRATED_BABYSTEPPING // EXPERIMENTAL integration of babystepping into the Stepper ISR
//#define BABYSTEP_WITHOUT_HOMING
+ //#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
//#define BABYSTEP_MILLIMETER_UNITS // Specify BABYSTEP_MULTIPLICATOR_(XY|Z) in mm instead of micro-steps
@@ -1582,7 +1621,6 @@
#if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING)
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
// Note: Extra time may be added to mitigate controller latency.
- //#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement).
//#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick 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.
@@ -1765,6 +1803,7 @@
#define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections
//#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles
//#define CNC_WORKSPACE_PLANES // Allow G2/G3 to operate in XY, ZX, or YZ planes
+ //#define SF_ARC_FIX // Enable only if using SkeinForge with "Arc Point" fillet procedure
#endif
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
@@ -1950,7 +1989,6 @@
* Be sure to turn off auto-retract during filament change.
*
* Note that M207 / M208 / M209 settings are saved to EEPROM.
- *
*/
//#define FWRETRACT
#if ENABLED(FWRETRACT)
@@ -1976,7 +2014,7 @@
* Universal tool change settings.
* Applies to all types of extruders except where explicitly noted.
*/
-#if EXTRUDERS > 1
+#if HAS_MULTI_EXTRUDER
// Z raise distance for tool-change, as needed for some extruders
#define TOOLCHANGE_ZRAISE 2 // (mm)
//#define TOOLCHANGE_ZRAISE_BEFORE_RETRACT // Apply raise before swap retraction (if enabled)
@@ -2040,7 +2078,7 @@
//#define TOOLCHANGE_PARK_X_ONLY // X axis only move
//#define TOOLCHANGE_PARK_Y_ONLY // Y axis only move
#endif
-#endif // EXTRUDERS > 1
+#endif // HAS_MULTI_EXTRUDER
/**
* Advanced Pause
@@ -3229,6 +3267,7 @@
//#define HOST_ACTION_COMMANDS
#if ENABLED(HOST_ACTION_COMMANDS)
//#define HOST_PROMPT_SUPPORT
+ //#define HOST_START_MENU_ITEM // Add a menu item that tells the host to start
#endif
/**
@@ -3336,6 +3375,7 @@
#define JOY_X_LIMITS { 5600, 8190-100, 8190+100, 10800 } // min, deadzone start, deadzone end, max
#define JOY_Y_LIMITS { 5600, 8250-100, 8250+100, 11000 }
#define JOY_Z_LIMITS { 4800, 8080-100, 8080+100, 11550 }
+ //#define JOYSTICK_DEBUG
#endif
/**
@@ -3413,10 +3453,10 @@
#if ENABLED(PRUSA_MMU2)
// Serial port used for communication with MMU2.
- // For AVR enable the UART port used for the MMU. (e.g., internalSerial)
+ // For AVR enable the UART port used for the MMU. (e.g., mmuSerial)
// For 32-bit boards check your HAL for available serial ports. (e.g., Serial2)
- #define INTERNAL_SERIAL_PORT 2
- #define MMU2_SERIAL internalSerial
+ #define MMU2_SERIAL_PORT 2
+ #define MMU2_SERIAL mmuSerial
// Use hardware reset for MMU if a pin is defined for it
//#define MMU2_RST_PIN 23
@@ -3467,7 +3507,7 @@
*/
//#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 MMU_LOADING_ATTEMPTS_NR 5 // max. number of attempts to load filament if first load fail
#endif
/**
@@ -3519,6 +3559,11 @@
//
//#define M100_FREE_MEMORY_WATCHER
+//
+// M42 - Set pin states
+//
+//#define DIRECT_PIN_CONTROL
+
//
// M43 - display pin status, toggle pins, watch pins, watch endstops & toggle LED, test servo probe
//
diff --git a/Marlin/Makefile b/Marlin/Makefile
index 68dd05bdfbad..49cb960b92fe 100644
--- a/Marlin/Makefile
+++ b/Marlin/Makefile
@@ -22,8 +22,10 @@
# (e.g. UPLOAD_PORT = /dev/tty.USB0). If the exact name of this file
# changes, you can use * as a wild card (e.g. UPLOAD_PORT = /dev/tty.usb*).
#
-# 3. Set the line containing "MCU" to match your board's processor.
-# Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
+# 3. Set the line containing "MCU" to match your board's processor. Set
+# "PROG_MCU" as the AVR part name corresponding to "MCU". You can use the
+# following command to get a list of correspondences: `avrdude -c alf -p x`
+# Older boards are atmega8 based, newer ones like Arduino Mini, Bluetooth
# or Diecimila have the atmega168. If you're using a LilyPad Arduino,
# change F_CPU to 8000000. If you are using Gen7 electronics, you
# probably need to use 20000000. Either way, you must regenerate
@@ -34,18 +36,18 @@
# 5. Type "make upload", reset your Arduino board, and press enter to
# upload your program to the Arduino board.
#
-# Note that all settings at the top of this file can be overriden from
+# Note that all settings at the top of this file can be overridden from
# the command line with, for example, "make HARDWARE_MOTHERBOARD=71"
#
# To compile for RAMPS (atmega2560) with Arduino 1.6.9 at root/arduino you would use...
#
# make ARDUINO_VERSION=10609 AVR_TOOLS_PATH=/root/arduino/hardware/tools/avr/bin/ \
-# HARDWARE_MOTHERBOARD=33 ARDUINO_INSTALL_DIR=/root/arduino
+# HARDWARE_MOTHERBOARD=1200 ARDUINO_INSTALL_DIR=/root/arduino
#
# To compile and upload simply add "upload" to the end of the line...
#
# make ARDUINO_VERSION=10609 AVR_TOOLS_PATH=/root/arduino/hardware/tools/avr/bin/ \
-# HARDWARE_MOTHERBOARD=33 ARDUINO_INSTALL_DIR=/root/arduino upload
+# HARDWARE_MOTHERBOARD=1200 ARDUINO_INSTALL_DIR=/root/arduino upload
#
# If uploading doesn't work try adding the parameter "AVRDUDE_PROGRAMMER=wiring" or
# start upload manually (using stk500) like so:
@@ -57,7 +59,26 @@
#
# This defines the board to compile for (see boards.h for your board's ID)
-HARDWARE_MOTHERBOARD ?= 11
+HARDWARE_MOTHERBOARD ?= 1020
+
+ifeq ($(OS),Windows_NT)
+ # Windows
+ ARDUINO_INSTALL_DIR ?= ${HOME}/Arduino
+ ARDUINO_USER_DIR ?= ${HOME}/Arduino
+else
+ UNAME_S := $(shell uname -s)
+ ifeq ($(UNAME_S),Linux)
+ # Linux
+ ARDUINO_INSTALL_DIR ?= /usr/share/arduino
+ ARDUINO_USER_DIR ?= ${HOME}/Arduino
+ endif
+ ifeq ($(UNAME_S),Darwin)
+ # Darwin (macOS)
+ ARDUINO_INSTALL_DIR ?= /Applications/Arduino.app/Contents/Java
+ ARDUINO_USER_DIR ?= ${HOME}/Documents/Arduino
+ AVR_TOOLS_PATH ?= /Applications/Arduino.app/Contents/Java/hardware/tools/avr/bin/
+ endif
+endif
# Arduino source install directory, and version number
# On most linuxes this will be /usr/share/arduino
@@ -67,32 +88,38 @@ ARDUINO_VERSION ?= 106
# The installed Libraries are in the User folder
ARDUINO_USER_DIR ?= ${HOME}/Arduino
-# You can optionally set a path to the avr-gcc tools. Requires a trailing slash. (ex: /usr/local/avr-gcc/bin)
+# You can optionally set a path to the avr-gcc tools.
+# Requires a trailing slash. For example, /usr/local/avr-gcc/bin/
AVR_TOOLS_PATH ?=
-#Programmer configuration
+# Programmer configuration
UPLOAD_RATE ?= 57600
AVRDUDE_PROGRAMMER ?= arduino
-# on most linuxes this will be /dev/ttyACM0 or /dev/ttyACM1
+# On most linuxes this will be /dev/ttyACM0 or /dev/ttyACM1
UPLOAD_PORT ?= /dev/ttyUSB0
-#Directory used to build files in, contains all the build files, from object files to the final hex file
-#on linux it is best to put an absolute path like /home/username/tmp .
+# Directory used to build files in, contains all the build files, from object
+# files to the final hex file on linux it is best to put an absolute path
+# like /home/username/tmp .
BUILD_DIR ?= applet
# This defines whether Liquid_TWI2 support will be built
LIQUID_TWI2 ?= 0
-# this defines if Wire is needed
+# This defines if Wire is needed
WIRE ?= 0
-# this defines if U8GLIB is needed (may require RELOC_WORKAROUND)
-U8GLIB ?= 1
+# This defines if Tone is needed (i.e SPEAKER is defined in Configuration.h)
+# Disabling this (and SPEAKER) saves approximatively 350 bytes of memory.
+TONE ?= 1
+
+# This defines if U8GLIB is needed (may require RELOC_WORKAROUND)
+U8GLIB ?= 0
-# this defines whether to include the Trinamic TMCStepper library
-TMC ?= 1
+# This defines whether to include the Trinamic TMCStepper library
+TMC ?= 0
-# this defines whether to include the AdaFruit NeoPixel library
+# This defines whether to include the AdaFruit NeoPixel library
NEOPIXEL ?= 0
############
@@ -208,7 +235,8 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1119)
else ifeq ($(HARDWARE_MOTHERBOARD),1120)
# Ultimaker (Older electronics. Pre 1.5.4. This is rare)
else ifeq ($(HARDWARE_MOTHERBOARD),1121)
- MCU ?= atmega1280
+ MCU ?= atmega1280
+ PROG_MCU ?= m1280
# Azteeg X3
else ifeq ($(HARDWARE_MOTHERBOARD),1122)
@@ -350,9 +378,11 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1320)
# Minitronics v1.0/1.1
else ifeq ($(HARDWARE_MOTHERBOARD),1400)
MCU ?= atmega1281
+ PROG_MCU ?= m1281
# Silvergate v1.0
else ifeq ($(HARDWARE_MOTHERBOARD),1401)
MCU ?= atmega1281
+ PROG_MCU ?= m1281
#
# Sanguinololu and Derivatives - ATmega644P, ATmega1284P
@@ -362,46 +392,57 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1401)
else ifeq ($(HARDWARE_MOTHERBOARD),1500)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
+ PROG_MCU ?= m644p
# Sanguinololu 1.2 and above
else ifeq ($(HARDWARE_MOTHERBOARD),1501)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
+ PROG_MCU ?= m644p
# Melzi
else ifeq ($(HARDWARE_MOTHERBOARD),1502)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
+ PROG_MCU ?= m644p
# Melzi V2.0
else ifeq ($(HARDWARE_MOTHERBOARD),1503)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
# Melzi with ATmega1284 (MaKr3d version)
else ifeq ($(HARDWARE_MOTHERBOARD),1504)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
# Melzi Creality3D board (for CR-10 etc)
else ifeq ($(HARDWARE_MOTHERBOARD),1505)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
# Melzi Malyan M150 board
else ifeq ($(HARDWARE_MOTHERBOARD),1506)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
# Tronxy X5S
else ifeq ($(HARDWARE_MOTHERBOARD),1507)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
# STB V1.1
else ifeq ($(HARDWARE_MOTHERBOARD),1508)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
# Azteeg X1
else ifeq ($(HARDWARE_MOTHERBOARD),1509)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
# Anet 1.0 (Melzi clone)
else ifeq ($(HARDWARE_MOTHERBOARD),1510)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
#
# Other ATmega644P, ATmega644, ATmega1284P
@@ -411,50 +452,61 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1510)
else ifeq ($(HARDWARE_MOTHERBOARD),1600)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
+ PROG_MCU ?= m644p
# Gen3+
else ifeq ($(HARDWARE_MOTHERBOARD),1601)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
+ PROG_MCU ?= m644p
# Gen6
else ifeq ($(HARDWARE_MOTHERBOARD),1602)
HARDWARE_VARIANT ?= Gen6
MCU ?= atmega644p
+ PROG_MCU ?= m644p
# Gen6 deluxe
else ifeq ($(HARDWARE_MOTHERBOARD),1603)
HARDWARE_VARIANT ?= Gen6
MCU ?= atmega644p
+ PROG_MCU ?= m644p
# Gen7 custom (Alfons3 Version)
else ifeq ($(HARDWARE_MOTHERBOARD),1604)
HARDWARE_VARIANT ?= Gen7
MCU ?= atmega644
+ PROG_MCU ?= m644
F_CPU ?= 20000000
# Gen7 v1.1, v1.2
else ifeq ($(HARDWARE_MOTHERBOARD),1605)
HARDWARE_VARIANT ?= Gen7
MCU ?= atmega644p
+ PROG_MCU ?= m644p
F_CPU ?= 20000000
# Gen7 v1.3
else ifeq ($(HARDWARE_MOTHERBOARD),1606)
HARDWARE_VARIANT ?= Gen7
MCU ?= atmega644p
+ PROG_MCU ?= m644p
F_CPU ?= 20000000
# Gen7 v1.4
else ifeq ($(HARDWARE_MOTHERBOARD),1607)
HARDWARE_VARIANT ?= Gen7
MCU ?= atmega1284p
+ PROG_MCU ?= m1284p
F_CPU ?= 20000000
# Alpha OMCA board
else ifeq ($(HARDWARE_MOTHERBOARD),1608)
HARDWARE_VARIANT ?= SanguinoA
MCU ?= atmega644
+ PROG_MCU ?= m644
# Final OMCA board
else ifeq ($(HARDWARE_MOTHERBOARD),1609)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
+ PROG_MCU ?= m644p
# Sethi 3D_1
else ifeq ($(HARDWARE_MOTHERBOARD),1610)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
+ PROG_MCU ?= m644p
#
# Teensyduino - AT90USB1286, AT90USB1286P
@@ -464,51 +516,60 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1610)
else ifeq ($(HARDWARE_MOTHERBOARD),1700)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
+ PROG_MCU ?= usb1286
# Printrboard (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),1701)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
+ PROG_MCU ?= usb1286
# Printrboard Revision F (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),1702)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
+ PROG_MCU ?= usb1286
# Brainwave (AT90USB646)
else ifeq ($(HARDWARE_MOTHERBOARD),1703)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb646
+ PROG_MCU ?= usb646
# Brainwave Pro (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),1704)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
+ PROG_MCU ?= usb1286
# SAV Mk-I (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),1705)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
+ PROG_MCU ?= usb1286
# Teensy++2.0 (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),1706)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
+ PROG_MCU ?= usb1286
# 5DPrint D8 Driver Board
else ifeq ($(HARDWARE_MOTHERBOARD),1707)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
+ PROG_MCU ?= usb1286
# UltiMachine Archim1 (with DRV8825 drivers)
else ifeq ($(HARDWARE_MOTHERBOARD),3023)
HARDWARE_VARIANT ?= archim
MCPU = cortex-m3
- F_CPU = 84000000L
+ F_CPU = 84000000
IS_MCU = 0
# UltiMachine Archim2 (with TMC2130 drivers)
else ifeq ($(HARDWARE_MOTHERBOARD),3024)
HARDWARE_VARIANT ?= archim
MCPU = cortex-m3
- F_CPU = 84000000L
+ F_CPU = 84000000
IS_MCU = 0
endif
# Be sure to regenerate speed_lookuptable.h with create_speed_lookuptable.py
# if you are setting this to something other than 16MHz
+# Do not put the UL suffix, it's done later on.
# Set to 16Mhz if not yet set.
F_CPU ?= 16000000
@@ -518,7 +579,8 @@ IS_MCU ?= 1
ifeq ($(IS_MCU),1)
# Set to arduino, ATmega2560 if not yet set.
HARDWARE_VARIANT ?= arduino
- MCU ?= atmega2560
+ MCU ?= atmega2560
+ PROG_MCU ?= m2560
TOOL_PREFIX = avr
MCU_FLAGS = -mmcu=$(MCU)
@@ -549,27 +611,36 @@ VPATH += $(BUILD_DIR)
VPATH += $(HARDWARE_SRC)
ifeq ($(HARDWARE_VARIANT), $(filter $(HARDWARE_VARIANT),arduino Teensy Sanguino))
-VPATH += $(ARDUINO_INSTALL_DIR)/hardware/marlin/avr/libraries/LiquidCrystal/src
-VPATH += $(ARDUINO_INSTALL_DIR)/hardware/marlin/avr/libraries/SPI
+ # 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
endif
ifeq ($(IS_MCU),1)
VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/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
endif
VPATH += $(ARDUINO_INSTALL_DIR)/libraries/LiquidCrystal/src
+
ifeq ($(LIQUID_TWI2), 1)
-VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire
-VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire/utility
-VPATH += $(ARDUINO_INSTALL_DIR)/libraries/LiquidTWI2
+ WIRE = 1
+ VPATH += $(ARDUINO_INSTALL_DIR)/libraries/LiquidTWI2
endif
ifeq ($(WIRE), 1)
-VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire
-VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire/utility
+ # Old libraries (avr-core 1.6.21 / Arduino < 1.6.8)
+ 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
endif
ifeq ($(NEOPIXEL), 1)
VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Adafruit_NeoPixel
@@ -641,13 +712,23 @@ ifeq ($(WIRE), 1)
LIB_CXXSRC += Wire.cpp
endif
+ifeq ($(TONE), 1)
+ LIB_CXXSRC += Tone.cpp
+endif
+
ifeq ($(U8GLIB), 1)
LIB_CXXSRC += U8glib.cpp
- LIB_SRC += u8g_ll_api.c u8g_bitmap.c u8g_clip.c u8g_com_null.c u8g_delay.c u8g_page.c u8g_pb.c u8g_pb16h1.c u8g_rect.c u8g_state.c u8g_font.c u8g_font_6x13.c u8g_font_04b_03.c u8g_font_5x8.c
+ LIB_SRC += u8g_ll_api.c u8g_bitmap.c u8g_clip.c u8g_com_null.c u8g_delay.c \
+ u8g_page.c u8g_pb.c u8g_pb16h1.c u8g_rect.c u8g_state.c u8g_font.c \
+ u8g_font_6x13.c u8g_font_04b_03.c u8g_font_5x8.c
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
+ 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
endif
ifeq ($(RELOC_WORKAROUND), 1)
@@ -689,17 +770,23 @@ REMOVE = rm -f
MV = mv -f
# Place -D or -U options here
-CDEFS = -DF_CPU=$(F_CPU) ${addprefix -D , $(DEFINES)} -DARDUINO=$(ARDUINO_VERSION)
+CDEFS = -DF_CPU=$(F_CPU)UL ${addprefix -D , $(DEFINES)} -DARDUINO=$(ARDUINO_VERSION)
CXXDEFS = $(CDEFS)
ifeq ($(HARDWARE_VARIANT), Teensy)
- CDEFS += -DUSB_SERIAL
+ CDEFS += -DUSB_SERIAL
LIB_SRC += usb.c pins_teensy.c
LIB_CXXSRC += usb_api.cpp
else ifeq ($(HARDWARE_VARIANT), archim)
- CDEFS += -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSB_VID=0x27b1 -DUSB_PID=0x0001 -DUSBCON '-DUSB_MANUFACTURER="UltiMachine"' '-DUSB_PRODUCT_STRING="Archim"'
- LIB_CXXSRC += variant.cpp IPAddress.cpp Reset.cpp RingBuffer.cpp Stream.cpp UARTClass.cpp USARTClass.cpp abi.cpp new.cpp watchdog.cpp CDC.cpp PluggableUSB.cpp USBCore.cpp
+ CDEFS += -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__
+ CDEFS += -DUSB_VID=0x27B1 -DUSB_PID=0x0001 -DUSBCON
+ CDEFS += '-DUSB_MANUFACTURER="UltiMachine"' '-DUSB_PRODUCT_STRING="Archim"'
+
+ LIB_CXXSRC += variant.cpp IPAddress.cpp Reset.cpp RingBuffer.cpp Stream.cpp \
+ UARTClass.cpp USARTClass.cpp abi.cpp new.cpp watchdog.cpp CDC.cpp \
+ PluggableUSB.cpp USBCore.cpp
+
LIB_SRC += cortex_handlers.c iar_calls_sam3.c syscalls_sam3.c dtostrf.c itoa.c
ifeq ($(U8GLIB), 1)
@@ -725,16 +812,20 @@ CTUNING = -fsigned-char -funsigned-bitfields -fno-exceptions \
ifneq ($(HARDWARE_MOTHERBOARD),)
CTUNING += -DMOTHERBOARD=${HARDWARE_MOTHERBOARD}
endif
+
#CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
CXXEXTRA = -fno-use-cxa-atexit -fno-threadsafe-statics -fno-rtti
CFLAGS := $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CEXTRA) $(CTUNING) $(CSTANDARD)
CXXFLAGS := $(CDEFS) $(CINCS) -O$(OPT) $(CXXEXTRA) $(CTUNING) $(CXXSTANDARD)
ASFLAGS := $(CDEFS)
#ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
+
ifeq ($(HARDWARE_VARIANT), archim)
LD_PREFIX = -Wl,--gc-sections,-Map,Marlin.ino.map,--cref,--check-sections,--entry=Reset_Handler,--unresolved-symbols=report-all,--warn-common,--warn-section-align
LD_SUFFIX = $(LDLIBS)
- LDFLAGS = -lm -T$(LDSCRIPT) -u _sbrk -u link -u _close -u _fstat -u _isatty -u _lseek -u _read -u _write -u _exit -u kill -u _getpid
+
+ LDFLAGS = -lm -T$(LDSCRIPT) -u _sbrk -u link -u _close -u _fstat -u _isatty
+ LDFLAGS += -u _lseek -u _read -u _write -u _exit -u kill -u _getpid
else
LD_PREFIX = -Wl,--gc-sections,--relax
LDFLAGS = -lm
@@ -750,7 +841,7 @@ else
AVRDUDE_CONF = $(ARDUINO_INSTALL_DIR)/hardware/tools/avr/etc/avrdude.conf
endif
AVRDUDE_FLAGS = -D -C$(AVRDUDE_CONF) \
- -p$(MCU) -P$(AVRDUDE_PORT) -c$(AVRDUDE_PROGRAMMER) \
+ -p$(PROG_MCU) -P$(AVRDUDE_PORT) -c$(AVRDUDE_PROGRAMMER) \
-b$(UPLOAD_RATE)
# Since Marlin 2.0, the source files may be distributed into several
@@ -851,7 +942,7 @@ extcoff: $(TARGET).elf
.elf.eep:
-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
- --change-section-lma .eeprom=0 -O $(FORMAT) $< $@
+ --change-section-lma .eeprom=0 -O $(FORMAT) $< $@
# Create extended listing file from ELF output file.
.elf.lss:
@@ -865,7 +956,7 @@ extcoff: $(TARGET).elf
$(BUILD_DIR)/$(TARGET).elf: $(OBJ) Configuration.h
$(Pecho) " CXX $@"
- $P $(CC) $(LD_PREFIX) $(ALL_CXXFLAGS) -o $@ -L. $(OBJ) $(LDFLAGS) $(LD_SUFFIX)
+ $P $(CXX) $(LD_PREFIX) $(ALL_CXXFLAGS) -o $@ -L. $(OBJ) $(LDFLAGS) $(LD_SUFFIX)
# Object files that were found in "src" will be stored in $(BUILD_DIR)
# in directories that mirror the structure of "src"
diff --git a/Marlin/Version.h b/Marlin/Version.h
index fe0724fbfcb1..f642fec7567a 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -28,7 +28,7 @@
/**
* Marlin release version identifier
*/
-//#define SHORT_BUILD_VERSION "bugfix-2.0.x"
+//#define SHORT_BUILD_VERSION "2.0.7.1"
/**
* Verbose version identifier which should contain a reference to the location
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2019-07-10"
+//#define STRING_DISTRIBUTION_DATE "2020-07-09"
/**
* Defines a generic printer name to be output to the LCD after booting Marlin.
diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h
index 609375e386e8..ce15ed29fb3a 100644
--- a/Marlin/src/HAL/AVR/HAL.h
+++ b/Marlin/src/HAL/AVR/HAL.h
@@ -15,6 +15,7 @@
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see .
+ *
*/
#pragma once
@@ -81,54 +82,29 @@ typedef int8_t pin_t;
// Serial ports
#ifdef USBCON
- #if ENABLED(BLUETOOTH)
- #define MYSERIAL0 bluetoothSerial
- #else
- #define MYSERIAL0 Serial
- #endif
- #define NUM_SERIAL 1
+ #define MYSERIAL0 TERN(BLUETOOTH, bluetoothSerial, Serial)
#else
#if !WITHIN(SERIAL_PORT, -1, 3)
#error "SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
-
#define MYSERIAL0 customizedSerial1
#ifdef SERIAL_PORT_2
#if !WITHIN(SERIAL_PORT_2, -1, 3)
#error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
- #elif SERIAL_PORT_2 == SERIAL_PORT
- #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration."
#endif
#define MYSERIAL1 customizedSerial2
- #define NUM_SERIAL 2
- #else
- #define NUM_SERIAL 1
#endif
#endif
-#ifdef DGUS_SERIAL_PORT
- #if !WITHIN(DGUS_SERIAL_PORT, -1, 3)
- #error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration."
- #elif DGUS_SERIAL_PORT == SERIAL_PORT
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
- #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
+#ifdef LCD_SERIAL_PORT
+ #if !WITHIN(LCD_SERIAL_PORT, -1, 3)
+ #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
- #define DGUS_SERIAL internalDgusSerial
-
- #define DGUS_SERIAL_GET_TX_BUFFER_FREE DGUS_SERIAL.get_tx_buffer_free
-#endif
-
-#ifdef ANYCUBIC_LCD_SERIAL_PORT
- #if !WITHIN(ANYCUBIC_LCD_SERIAL_PORT, -1, 3)
- #error "ANYCUBIC_LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
- #elif ANYCUBIC_LCD_SERIAL_PORT == SERIAL_PORT
- #error "ANYCUBIC_LCD_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
- #elif defined(SERIAL_PORT_2) && ANYCUBIC_LCD_SERIAL_PORT == SERIAL_PORT_2
- #error "ANYCUBIC_LCD_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
+ #define LCD_SERIAL lcdSerial
+ #if HAS_DGUS_LCD
+ #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.get_tx_buffer_free()
#endif
- #define ANYCUBIC_LCD_SERIAL anycubicLcdSerial
#endif
// ------------------------
@@ -144,6 +120,8 @@ void HAL_init();
inline void HAL_clear_reset_source() { MCUSR = 0; }
inline uint8_t HAL_get_reset_source() { return MCUSR; }
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
extern "C" {
diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp
index 3d44a3f59ffc..63599efd4132 100644
--- a/Marlin/src/HAL/AVR/MarlinSerial.cpp
+++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp
@@ -40,407 +40,370 @@
#if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))
- #include "MarlinSerial.h"
- #include "../../MarlinCore.h"
+#include "MarlinSerial.h"
+#include "../../MarlinCore.h"
+
+#if ENABLED(DIRECT_STEPPING)
+ #include "../../feature/direct_stepping.h"
+#endif
+
+template typename MarlinSerial::ring_buffer_r MarlinSerial::rx_buffer = { 0, 0, { 0 } };
+template typename MarlinSerial::ring_buffer_t MarlinSerial::tx_buffer = { 0 };
+template bool MarlinSerial::_written = false;
+template uint8_t MarlinSerial::xon_xoff_state = MarlinSerial::XON_XOFF_CHAR_SENT | MarlinSerial::XON_CHAR;
+template uint8_t MarlinSerial::rx_dropped_bytes = 0;
+template uint8_t MarlinSerial::rx_buffer_overruns = 0;
+template uint8_t MarlinSerial::rx_framing_errors = 0;
+template typename MarlinSerial::ring_buffer_pos_t MarlinSerial::rx_max_enqueued = 0;
+
+// A SW memory barrier, to ensure GCC does not overoptimize loops
+#define sw_barrier() asm volatile("": : :"memory");
+
+#include "../../feature/e_parser.h"
+
+// "Atomically" read the RX head index value without disabling interrupts:
+// This MUST be called with RX interrupts enabled, and CAN'T be called
+// from the RX ISR itself!
+template
+FORCE_INLINE typename MarlinSerial::ring_buffer_pos_t MarlinSerial::atomic_read_rx_head() {
+ if (Cfg::RX_SIZE > 256) {
+ // Keep reading until 2 consecutive reads return the same value,
+ // meaning there was no update in-between caused by an interrupt.
+ // This works because serial RX interrupts happen at a slower rate
+ // than successive reads of a variable, so 2 consecutive reads with
+ // the same value means no interrupt updated it.
+ ring_buffer_pos_t vold, vnew = rx_buffer.head;
+ sw_barrier();
+ do {
+ vold = vnew;
+ vnew = rx_buffer.head;
+ sw_barrier();
+ } while (vold != vnew);
+ return vnew;
+ }
+ else {
+ // With an 8bit index, reads are always atomic. No need for special handling
+ return rx_buffer.head;
+ }
+}
+
+template
+volatile bool MarlinSerial::rx_tail_value_not_stable = false;
+template
+volatile uint16_t MarlinSerial::rx_tail_value_backup = 0;
+
+// Set RX tail index, taking into account the RX ISR could interrupt
+// the write to this variable in the middle - So a backup strategy
+// is used to ensure reads of the correct values.
+// -Must NOT be called from the RX ISR -
+template
+FORCE_INLINE void MarlinSerial::atomic_set_rx_tail(typename MarlinSerial::ring_buffer_pos_t value) {
+ if (Cfg::RX_SIZE > 256) {
+ // Store the new value in the backup
+ rx_tail_value_backup = value;
+ sw_barrier();
+ // Flag we are about to change the true value
+ rx_tail_value_not_stable = true;
+ sw_barrier();
+ // Store the new value
+ rx_buffer.tail = value;
+ sw_barrier();
+ // Signal the new value is completely stored into the value
+ rx_tail_value_not_stable = false;
+ sw_barrier();
+ }
+ else
+ rx_buffer.tail = value;
+}
+
+// Get the RX tail index, taking into account the read could be
+// interrupting in the middle of the update of that index value
+// -Called from the RX ISR -
+template
+FORCE_INLINE typename MarlinSerial::ring_buffer_pos_t MarlinSerial::atomic_read_rx_tail() {
+ if (Cfg::RX_SIZE > 256) {
+ // If the true index is being modified, return the backup value
+ if (rx_tail_value_not_stable) return rx_tail_value_backup;
+ }
+ // The true index is stable, return it
+ return rx_buffer.tail;
+}
+
+// (called with RX interrupts disabled)
+template
+FORCE_INLINE void MarlinSerial::store_rxd_char() {
+
+ static EmergencyParser::State emergency_state; // = EP_RESET
+
+ // This must read the R_UCSRA register before reading the received byte to detect error causes
+ if (Cfg::DROPPED_RX && B_DOR && !++rx_dropped_bytes) --rx_dropped_bytes;
+ if (Cfg::RX_OVERRUNS && B_DOR && !++rx_buffer_overruns) --rx_buffer_overruns;
+ if (Cfg::RX_FRAMING_ERRORS && B_FE && !++rx_framing_errors) --rx_framing_errors;
+
+ // Read the character from the USART
+ uint8_t c = R_UDR;
#if ENABLED(DIRECT_STEPPING)
- #include "../../feature/direct_stepping.h"
+ if (page_manager.maybe_store_rxd_char(c)) return;
#endif
- template typename MarlinSerial::ring_buffer_r MarlinSerial::rx_buffer = { 0, 0, { 0 } };
- template typename MarlinSerial::ring_buffer_t MarlinSerial::tx_buffer = { 0 };
- template bool MarlinSerial::_written = false;
- template uint8_t MarlinSerial::xon_xoff_state = MarlinSerial::XON_XOFF_CHAR_SENT | MarlinSerial::XON_CHAR;
- template uint8_t MarlinSerial::rx_dropped_bytes = 0;
- template uint8_t MarlinSerial::rx_buffer_overruns = 0;
- template uint8_t MarlinSerial::rx_framing_errors = 0;
- template typename MarlinSerial::ring_buffer_pos_t MarlinSerial::rx_max_enqueued = 0;
-
- // A SW memory barrier, to ensure GCC does not overoptimize loops
- #define sw_barrier() asm volatile("": : :"memory");
-
- #include "../../feature/e_parser.h"
-
- // "Atomically" read the RX head index value without disabling interrupts:
- // This MUST be called with RX interrupts enabled, and CAN'T be called
- // from the RX ISR itself!
- template
- FORCE_INLINE typename MarlinSerial::ring_buffer_pos_t MarlinSerial::atomic_read_rx_head() {
- if (Cfg::RX_SIZE > 256) {
- // Keep reading until 2 consecutive reads return the same value,
- // meaning there was no update in-between caused by an interrupt.
- // This works because serial RX interrupts happen at a slower rate
- // than successive reads of a variable, so 2 consecutive reads with
- // the same value means no interrupt updated it.
- ring_buffer_pos_t vold, vnew = rx_buffer.head;
- sw_barrier();
- do {
- vold = vnew;
- vnew = rx_buffer.head;
- sw_barrier();
- } while (vold != vnew);
- return vnew;
- }
- else {
- // With an 8bit index, reads are always atomic. No need for special handling
- return rx_buffer.head;
- }
- }
+ // Get the tail - Nothing can alter its value while this ISR is executing, but there's
+ // a chance that this ISR interrupted the main process while it was updating the index.
+ // The backup mechanism ensures the correct value is always returned.
+ const ring_buffer_pos_t t = atomic_read_rx_tail();
- template
- volatile bool MarlinSerial::rx_tail_value_not_stable = false;
- template
- volatile uint16_t MarlinSerial::rx_tail_value_backup = 0;
-
- // Set RX tail index, taking into account the RX ISR could interrupt
- // the write to this variable in the middle - So a backup strategy
- // is used to ensure reads of the correct values.
- // -Must NOT be called from the RX ISR -
- template
- FORCE_INLINE void MarlinSerial::atomic_set_rx_tail(typename MarlinSerial::ring_buffer_pos_t value) {
- if (Cfg::RX_SIZE > 256) {
- // Store the new value in the backup
- rx_tail_value_backup = value;
- sw_barrier();
- // Flag we are about to change the true value
- rx_tail_value_not_stable = true;
- sw_barrier();
- // Store the new value
- rx_buffer.tail = value;
- sw_barrier();
- // Signal the new value is completely stored into the value
- rx_tail_value_not_stable = false;
- sw_barrier();
- }
- else
- rx_buffer.tail = value;
- }
+ // Get the head pointer - This ISR is the only one that modifies its value, so it's safe to read here
+ ring_buffer_pos_t h = rx_buffer.head;
- // Get the RX tail index, taking into account the read could be
- // interrupting in the middle of the update of that index value
- // -Called from the RX ISR -
- template
- FORCE_INLINE typename MarlinSerial::ring_buffer_pos_t MarlinSerial::atomic_read_rx_tail() {
- if (Cfg::RX_SIZE > 256) {
- // If the true index is being modified, return the backup value
- if (rx_tail_value_not_stable) return rx_tail_value_backup;
- }
- // The true index is stable, return it
- return rx_buffer.tail;
- }
+ // Get the next element
+ ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
- // (called with RX interrupts disabled)
- template
- FORCE_INLINE void MarlinSerial::store_rxd_char() {
+ if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c);
+
+ // If the character is to be stored at the index just before the tail
+ // (such that the head would advance to the current tail), the RX FIFO is
+ // full, so don't write the character or advance the head.
+ if (i != t) {
+ rx_buffer.buffer[h] = c;
+ h = i;
+ }
+ else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
+ --rx_dropped_bytes;
- static EmergencyParser::State emergency_state; // = EP_RESET
+ if (Cfg::MAX_RX_QUEUED) {
+ // Calculate count of bytes stored into the RX buffer
+ const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
- // This must read the R_UCSRA register before reading the received byte to detect error causes
- if (Cfg::DROPPED_RX && B_DOR && !++rx_dropped_bytes) --rx_dropped_bytes;
- if (Cfg::RX_OVERRUNS && B_DOR && !++rx_buffer_overruns) --rx_buffer_overruns;
- if (Cfg::RX_FRAMING_ERRORS && B_FE && !++rx_framing_errors) --rx_framing_errors;
+ // Keep track of the maximum count of enqueued bytes
+ NOLESS(rx_max_enqueued, rx_count);
+ }
- // Read the character from the USART
- uint8_t c = R_UDR;
+ if (Cfg::XONOFF) {
+ // If the last char that was sent was an XON
+ if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {
- #if ENABLED(DIRECT_STEPPING)
- if (page_manager.maybe_store_rxd_char(c)) return;
- #endif
+ // Bytes stored into the RX buffer
+ const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
- // Get the tail - Nothing can alter its value while this ISR is executing, but there's
- // a chance that this ISR interrupted the main process while it was updating the index.
- // The backup mechanism ensures the correct value is always returned.
- const ring_buffer_pos_t t = atomic_read_rx_tail();
+ // If over 12.5% of RX buffer capacity, send XOFF before running out of
+ // RX buffer space .. 325 bytes @ 250kbits/s needed to let the host react
+ // and stop sending bytes. This translates to 13mS propagation time.
+ if (rx_count >= (Cfg::RX_SIZE) / 8) {
- // Get the head pointer - This ISR is the only one that modifies its value, so it's safe to read here
- ring_buffer_pos_t h = rx_buffer.head;
+ // At this point, definitely no TX interrupt was executing, since the TX ISR can't be preempted.
+ // Don't enable the TX interrupt here as a means to trigger the XOFF char, because if it happens
+ // to be in the middle of trying to disable the RX interrupt in the main program, eventually the
+ // enabling of the TX interrupt could be undone. The ONLY reliable thing this can do to ensure
+ // the sending of the XOFF char is to send it HERE AND NOW.
- // Get the next element
- ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
+ // About to send the XOFF char
+ xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
- if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c);
+ // Wait until the TX register becomes empty and send it - Here there could be a problem
+ // - While waiting for the TX register to empty, the RX register could receive a new
+ // character. This must also handle that situation!
+ while (!B_UDRE) {
- // If the character is to be stored at the index just before the tail
- // (such that the head would advance to the current tail), the RX FIFO is
- // full, so don't write the character or advance the head.
- if (i != t) {
- rx_buffer.buffer[h] = c;
- h = i;
- }
- else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
- --rx_dropped_bytes;
+ if (B_RXC) {
+ // A char arrived while waiting for the TX buffer to be empty - Receive and process it!
- if (Cfg::MAX_RX_QUEUED) {
- // Calculate count of bytes stored into the RX buffer
- const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
+ i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
- // Keep track of the maximum count of enqueued bytes
- NOLESS(rx_max_enqueued, rx_count);
- }
+ // Read the character from the USART
+ c = R_UDR;
- if (Cfg::XONOFF) {
- // If the last char that was sent was an XON
- if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {
-
- // Bytes stored into the RX buffer
- const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
-
- // If over 12.5% of RX buffer capacity, send XOFF before running out of
- // RX buffer space .. 325 bytes @ 250kbits/s needed to let the host react
- // and stop sending bytes. This translates to 13mS propagation time.
- if (rx_count >= (Cfg::RX_SIZE) / 8) {
-
- // At this point, definitely no TX interrupt was executing, since the TX ISR can't be preempted.
- // Don't enable the TX interrupt here as a means to trigger the XOFF char, because if it happens
- // to be in the middle of trying to disable the RX interrupt in the main program, eventually the
- // enabling of the TX interrupt could be undone. The ONLY reliable thing this can do to ensure
- // the sending of the XOFF char is to send it HERE AND NOW.
-
- // About to send the XOFF char
- xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
-
- // Wait until the TX register becomes empty and send it - Here there could be a problem
- // - While waiting for the TX register to empty, the RX register could receive a new
- // character. This must also handle that situation!
- while (!B_UDRE) {
-
- if (B_RXC) {
- // A char arrived while waiting for the TX buffer to be empty - Receive and process it!
-
- i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
-
- // Read the character from the USART
- c = R_UDR;
-
- if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c);
-
- // If the character is to be stored at the index just before the tail
- // (such that the head would advance to the current tail), the FIFO is
- // full, so don't write the character or advance the head.
- if (i != t) {
- rx_buffer.buffer[h] = c;
- h = i;
- }
- else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
- --rx_dropped_bytes;
- }
- sw_barrier();
- }
+ if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c);
- R_UDR = XOFF_CHAR;
-
- // Clear the TXC bit -- "can be cleared by writing a one to its bit
- // location". This makes sure flush() won't return until the bytes
- // actually got written
- B_TXC = 1;
-
- // At this point there could be a race condition between the write() function
- // and this sending of the XOFF char. This interrupt could happen between the
- // wait to be empty TX buffer loop and the actual write of the character. Since
- // the TX buffer is full because it's sending the XOFF char, the only way to be
- // sure the write() function will succeed is to wait for the XOFF char to be
- // completely sent. Since an extra character could be received during the wait
- // it must also be handled!
- while (!B_UDRE) {
-
- if (B_RXC) {
- // A char arrived while waiting for the TX buffer to be empty - Receive and process it!
-
- i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
-
- // Read the character from the USART
- c = R_UDR;
-
- if (Cfg::EMERGENCYPARSER)
- emergency_parser.update(emergency_state, c);
-
- // If the character is to be stored at the index just before the tail
- // (such that the head would advance to the current tail), the FIFO is
- // full, so don't write the character or advance the head.
- if (i != t) {
- rx_buffer.buffer[h] = c;
- h = i;
- }
- else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
- --rx_dropped_bytes;
+ // If the character is to be stored at the index just before the tail
+ // (such that the head would advance to the current tail), the FIFO is
+ // full, so don't write the character or advance the head.
+ if (i != t) {
+ rx_buffer.buffer[h] = c;
+ h = i;
}
- sw_barrier();
+ else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
+ --rx_dropped_bytes;
}
-
- // At this point everything is ready. The write() function won't
- // have any issues writing to the UART TX register if it needs to!
+ sw_barrier();
}
- }
- }
- // Store the new head value - The main loop will retry until the value is stable
- rx_buffer.head = h;
- }
+ R_UDR = XOFF_CHAR;
- // (called with TX irqs disabled)
- template
- FORCE_INLINE void MarlinSerial::_tx_udr_empty_irq() {
- if (Cfg::TX_SIZE > 0) {
- // Read positions
- uint8_t t = tx_buffer.tail;
- const uint8_t h = tx_buffer.head;
+ // Clear the TXC bit -- "can be cleared by writing a one to its bit
+ // location". This makes sure flush() won't return until the bytes
+ // actually got written
+ B_TXC = 1;
- if (Cfg::XONOFF) {
- // If an XON char is pending to be sent, do it now
- if (xon_xoff_state == XON_CHAR) {
+ // At this point there could be a race condition between the write() function
+ // and this sending of the XOFF char. This interrupt could happen between the
+ // wait to be empty TX buffer loop and the actual write of the character. Since
+ // the TX buffer is full because it's sending the XOFF char, the only way to be
+ // sure the write() function will succeed is to wait for the XOFF char to be
+ // completely sent. Since an extra character could be received during the wait
+ // it must also be handled!
+ while (!B_UDRE) {
- // Send the character
- R_UDR = XON_CHAR;
+ if (B_RXC) {
+ // A char arrived while waiting for the TX buffer to be empty - Receive and process it!
- // clear the TXC bit -- "can be cleared by writing a one to its bit
- // location". This makes sure flush() won't return until the bytes
- // actually got written
- B_TXC = 1;
+ i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
- // Remember we sent it.
- xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
+ // Read the character from the USART
+ c = R_UDR;
- // If nothing else to transmit, just disable TX interrupts.
- if (h == t) B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
+ if (Cfg::EMERGENCYPARSER)
+ emergency_parser.update(emergency_state, c);
- return;
+ // If the character is to be stored at the index just before the tail
+ // (such that the head would advance to the current tail), the FIFO is
+ // full, so don't write the character or advance the head.
+ if (i != t) {
+ rx_buffer.buffer[h] = c;
+ h = i;
+ }
+ else if (Cfg::DROPPED_RX && !++rx_dropped_bytes)
+ --rx_dropped_bytes;
+ }
+ sw_barrier();
}
- }
- // If nothing to transmit, just disable TX interrupts. This could
- // happen as the result of the non atomicity of the disabling of RX
- // interrupts that could end reenabling TX interrupts as a side effect.
- if (h == t) {
- B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
- return;
+ // At this point everything is ready. The write() function won't
+ // have any issues writing to the UART TX register if it needs to!
}
-
- // There is something to TX, Send the next byte
- const uint8_t c = tx_buffer.buffer[t];
- t = (t + 1) & (Cfg::TX_SIZE - 1);
- R_UDR = c;
- tx_buffer.tail = t;
-
- // Clear the TXC bit (by writing a one to its bit location).
- // Ensures flush() won't return until the bytes are actually written/
- B_TXC = 1;
-
- // Disable interrupts if there is nothing to transmit following this byte
- if (h == t) B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
- }
- }
-
- // Public Methods
- template
- void MarlinSerial::begin(const long baud) {
- uint16_t baud_setting;
- bool useU2X = true;
-
- #if F_CPU == 16000000UL && SERIAL_PORT == 0
- // Hard-coded exception for compatibility with the bootloader shipped
- // with the Duemilanove and previous boards, and the firmware on the
- // 8U2 on the Uno and Mega 2560.
- if (baud == 57600) useU2X = false;
- #endif
-
- R_UCSRA = 0;
- if (useU2X) {
- B_U2X = 1;
- baud_setting = (F_CPU / 4 / baud - 1) / 2;
}
- else
- baud_setting = (F_CPU / 8 / baud - 1) / 2;
-
- // assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register)
- R_UBRRH = baud_setting >> 8;
- R_UBRRL = baud_setting;
-
- B_RXEN = 1;
- B_TXEN = 1;
- B_RXCIE = 1;
- if (Cfg::TX_SIZE > 0) B_UDRIE = 0;
- _written = false;
}
- template
- void MarlinSerial::end() {
- B_RXEN = 0;
- B_TXEN = 0;
- B_RXCIE = 0;
- B_UDRIE = 0;
- }
+ // Store the new head value - The main loop will retry until the value is stable
+ rx_buffer.head = h;
+}
- template
- int MarlinSerial::peek() {
- const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail;
- return h == t ? -1 : rx_buffer.buffer[t];
- }
+// (called with TX irqs disabled)
+template
+FORCE_INLINE void MarlinSerial::_tx_udr_empty_irq() {
+ if (Cfg::TX_SIZE > 0) {
+ // Read positions
+ uint8_t t = tx_buffer.tail;
+ const uint8_t h = tx_buffer.head;
- template
- int MarlinSerial::read() {
- const ring_buffer_pos_t h = atomic_read_rx_head();
+ if (Cfg::XONOFF) {
+ // If an XON char is pending to be sent, do it now
+ if (xon_xoff_state == XON_CHAR) {
- // Read the tail. Main thread owns it, so it is safe to directly read it
- ring_buffer_pos_t t = rx_buffer.tail;
+ // Send the character
+ R_UDR = XON_CHAR;
- // If nothing to read, return now
- if (h == t) return -1;
+ // clear the TXC bit -- "can be cleared by writing a one to its bit
+ // location". This makes sure flush() won't return until the bytes
+ // actually got written
+ B_TXC = 1;
- // Get the next char
- const int v = rx_buffer.buffer[t];
- t = (ring_buffer_pos_t)(t + 1) & (Cfg::RX_SIZE - 1);
+ // Remember we sent it.
+ xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
- // Advance tail - Making sure the RX ISR will always get an stable value, even
- // if it interrupts the writing of the value of that variable in the middle.
- atomic_set_rx_tail(t);
+ // If nothing else to transmit, just disable TX interrupts.
+ if (h == t) B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
- if (Cfg::XONOFF) {
- // If the XOFF char was sent, or about to be sent...
- if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
- // Get count of bytes in the RX buffer
- const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
- if (rx_count < (Cfg::RX_SIZE) / 10) {
- if (Cfg::TX_SIZE > 0) {
- // Signal we want an XON character to be sent.
- xon_xoff_state = XON_CHAR;
- // Enable TX ISR. Non atomic, but it will eventually enable them
- B_UDRIE = 1;
- }
- else {
- // If not using TX interrupts, we must send the XON char now
- xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
- while (!B_UDRE) sw_barrier();
- R_UDR = XON_CHAR;
- }
- }
+ return;
}
}
- return v;
- }
+ // If nothing to transmit, just disable TX interrupts. This could
+ // happen as the result of the non atomicity of the disabling of RX
+ // interrupts that could end reenabling TX interrupts as a side effect.
+ if (h == t) {
+ B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
+ return;
+ }
- template
- typename MarlinSerial::ring_buffer_pos_t MarlinSerial::available() {
- const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail;
- return (ring_buffer_pos_t)(Cfg::RX_SIZE + h - t) & (Cfg::RX_SIZE - 1);
+ // There is something to TX, Send the next byte
+ const uint8_t c = tx_buffer.buffer[t];
+ t = (t + 1) & (Cfg::TX_SIZE - 1);
+ R_UDR = c;
+ tx_buffer.tail = t;
+
+ // Clear the TXC bit (by writing a one to its bit location).
+ // Ensures flush() won't return until the bytes are actually written/
+ B_TXC = 1;
+
+ // Disable interrupts if there is nothing to transmit following this byte
+ if (h == t) B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
}
+}
- template
- void MarlinSerial::flush() {
+// Public Methods
+template
+void MarlinSerial::begin(const long baud) {
+ uint16_t baud_setting;
+ bool useU2X = true;
- // Set the tail to the head:
- // - Read the RX head index in a safe way. (See atomic_read_rx_head.)
- // - Set the tail, making sure the RX ISR will always get a stable value, even
- // if it interrupts the writing of the value of that variable in the middle.
- atomic_set_rx_tail(atomic_read_rx_head());
+ #if F_CPU == 16000000UL && SERIAL_PORT == 0
+ // Hard-coded exception for compatibility with the bootloader shipped
+ // with the Duemilanove and previous boards, and the firmware on the
+ // 8U2 on the Uno and Mega 2560.
+ if (baud == 57600) useU2X = false;
+ #endif
- if (Cfg::XONOFF) {
- // If the XOFF char was sent, or about to be sent...
- if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
+ R_UCSRA = 0;
+ if (useU2X) {
+ B_U2X = 1;
+ baud_setting = (F_CPU / 4 / baud - 1) / 2;
+ }
+ else
+ baud_setting = (F_CPU / 8 / baud - 1) / 2;
+
+ // assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register)
+ R_UBRRH = baud_setting >> 8;
+ R_UBRRL = baud_setting;
+
+ B_RXEN = 1;
+ B_TXEN = 1;
+ B_RXCIE = 1;
+ if (Cfg::TX_SIZE > 0) B_UDRIE = 0;
+ _written = false;
+}
+
+template
+void MarlinSerial::end() {
+ B_RXEN = 0;
+ B_TXEN = 0;
+ B_RXCIE = 0;
+ B_UDRIE = 0;
+}
+
+template
+int MarlinSerial::peek() {
+ const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail;
+ return h == t ? -1 : rx_buffer.buffer[t];
+}
+
+template
+int MarlinSerial::read() {
+ const ring_buffer_pos_t h = atomic_read_rx_head();
+
+ // Read the tail. Main thread owns it, so it is safe to directly read it
+ ring_buffer_pos_t t = rx_buffer.tail;
+
+ // If nothing to read, return now
+ if (h == t) return -1;
+
+ // Get the next char
+ const int v = rx_buffer.buffer[t];
+ t = (ring_buffer_pos_t)(t + 1) & (Cfg::RX_SIZE - 1);
+
+ // Advance tail - Making sure the RX ISR will always get an stable value, even
+ // if it interrupts the writing of the value of that variable in the middle.
+ atomic_set_rx_tail(t);
+
+ if (Cfg::XONOFF) {
+ // If the XOFF char was sent, or about to be sent...
+ if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
+ // Get count of bytes in the RX buffer
+ const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1);
+ if (rx_count < (Cfg::RX_SIZE) / 10) {
if (Cfg::TX_SIZE > 0) {
// Signal we want an XON character to be sent.
xon_xoff_state = XON_CHAR;
- // Enable TX ISR. Non atomic, but it will eventually enable it.
+ // Enable TX ISR. Non atomic, but it will eventually enable them
B_UDRIE = 1;
}
else {
@@ -453,363 +416,384 @@
}
}
- template
- void MarlinSerial::write(const uint8_t c) {
- if (Cfg::TX_SIZE == 0) {
-
- _written = true;
- while (!B_UDRE) sw_barrier();
- R_UDR = c;
-
- }
- else {
-
- _written = true;
-
- // If the TX interrupts are disabled and the data register
- // is empty, just write the byte to the data register and
- // be done. This shortcut helps significantly improve the
- // effective datarate at high (>500kbit/s) bitrates, where
- // interrupt overhead becomes a slowdown.
- // Yes, there is a race condition between the sending of the
- // XOFF char at the RX ISR, but it is properly handled there
- if (!B_UDRIE && B_UDRE) {
- R_UDR = c;
-
- // clear the TXC bit -- "can be cleared by writing a one to its bit
- // location". This makes sure flush() won't return until the bytes
- // actually got written
- B_TXC = 1;
- return;
- }
-
- const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
-
- // If global interrupts are disabled (as the result of being called from an ISR)...
- if (!ISRS_ENABLED()) {
-
- // Make room by polling if it is possible to transmit, and do so!
- while (i == tx_buffer.tail) {
-
- // If we can transmit another byte, do it.
- if (B_UDRE) _tx_udr_empty_irq();
-
- // Make sure compiler rereads tx_buffer.tail
- sw_barrier();
- }
+ return v;
+}
+
+template
+typename MarlinSerial::ring_buffer_pos_t MarlinSerial::available() {
+ const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail;
+ return (ring_buffer_pos_t)(Cfg::RX_SIZE + h - t) & (Cfg::RX_SIZE - 1);
+}
+
+template
+void MarlinSerial::flush() {
+
+ // Set the tail to the head:
+ // - Read the RX head index in a safe way. (See atomic_read_rx_head.)
+ // - Set the tail, making sure the RX ISR will always get a stable value, even
+ // if it interrupts the writing of the value of that variable in the middle.
+ atomic_set_rx_tail(atomic_read_rx_head());
+
+ if (Cfg::XONOFF) {
+ // If the XOFF char was sent, or about to be sent...
+ if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
+ if (Cfg::TX_SIZE > 0) {
+ // Signal we want an XON character to be sent.
+ xon_xoff_state = XON_CHAR;
+ // Enable TX ISR. Non atomic, but it will eventually enable it.
+ B_UDRIE = 1;
}
else {
- // Interrupts are enabled, just wait until there is space
- while (i == tx_buffer.tail) sw_barrier();
+ // If not using TX interrupts, we must send the XON char now
+ xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
+ while (!B_UDRE) sw_barrier();
+ R_UDR = XON_CHAR;
}
-
- // Store new char. head is always safe to move
- tx_buffer.buffer[tx_buffer.head] = c;
- tx_buffer.head = i;
-
- // Enable TX ISR - Non atomic, but it will eventually enable TX ISR
- B_UDRIE = 1;
}
}
+}
- template
- void MarlinSerial::flushTX() {
+template
+void MarlinSerial::write(const uint8_t c) {
+ if (Cfg::TX_SIZE == 0) {
- if (Cfg::TX_SIZE == 0) {
- // No bytes written, no need to flush. This special case is needed since there's
- // no way to force the TXC (transmit complete) bit to 1 during initialization.
- if (!_written) return;
+ _written = true;
+ while (!B_UDRE) sw_barrier();
+ R_UDR = c;
- // Wait until everything was transmitted
- while (!B_TXC) sw_barrier();
+ }
+ else {
- // At this point nothing is queued anymore (DRIE is disabled) and
- // the hardware finished transmission (TXC is set).
+ _written = true;
- }
- else {
+ // If the TX interrupts are disabled and the data register
+ // is empty, just write the byte to the data register and
+ // be done. This shortcut helps significantly improve the
+ // effective datarate at high (>500kbit/s) bitrates, where
+ // interrupt overhead becomes a slowdown.
+ // Yes, there is a race condition between the sending of the
+ // XOFF char at the RX ISR, but it is properly handled there
+ if (!B_UDRIE && B_UDRE) {
+ R_UDR = c;
- // No bytes written, no need to flush. This special case is needed since there's
- // no way to force the TXC (transmit complete) bit to 1 during initialization.
- if (!_written) return;
+ // clear the TXC bit -- "can be cleared by writing a one to its bit
+ // location". This makes sure flush() won't return until the bytes
+ // actually got written
+ B_TXC = 1;
+ return;
+ }
- // If global interrupts are disabled (as the result of being called from an ISR)...
- if (!ISRS_ENABLED()) {
+ const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
- // Wait until everything was transmitted - We must do polling, as interrupts are disabled
- while (tx_buffer.head != tx_buffer.tail || !B_TXC) {
+ // If global interrupts are disabled (as the result of being called from an ISR)...
+ if (!ISRS_ENABLED()) {
- // If there is more space, send an extra character
- if (B_UDRE) _tx_udr_empty_irq();
+ // Make room by polling if it is possible to transmit, and do so!
+ while (i == tx_buffer.tail) {
- sw_barrier();
- }
+ // If we can transmit another byte, do it.
+ if (B_UDRE) _tx_udr_empty_irq();
+ // Make sure compiler rereads tx_buffer.tail
+ sw_barrier();
}
- else {
- // Wait until everything was transmitted
- while (tx_buffer.head != tx_buffer.tail || !B_TXC) sw_barrier();
- }
-
- // At this point nothing is queued anymore (DRIE is disabled) and
- // the hardware finished transmission (TXC is set).
}
- }
-
- /**
- * Imports from print.h
- */
-
- template
- void MarlinSerial::print(char c, int base) {
- print((long)c, base);
- }
-
- template
- void MarlinSerial::print(unsigned char b, int base) {
- print((unsigned long)b, base);
- }
-
- template
- void MarlinSerial::print(int n, int base) {
- print((long)n, base);
- }
-
- template
- void MarlinSerial::print(unsigned int n, int base) {
- print((unsigned long)n, base);
- }
-
- template
- void MarlinSerial::print(long n, int base) {
- if (base == 0) write(n);
- else if (base == 10) {
- if (n < 0) { print('-'); n = -n; }
- printNumber(n, 10);
+ else {
+ // Interrupts are enabled, just wait until there is space
+ while (i == tx_buffer.tail) sw_barrier();
}
- else
- printNumber(n, base);
- }
- template
- void MarlinSerial::print(unsigned long n, int base) {
- if (base == 0) write(n);
- else printNumber(n, base);
- }
+ // Store new char. head is always safe to move
+ tx_buffer.buffer[tx_buffer.head] = c;
+ tx_buffer.head = i;
- template
- void MarlinSerial::print(double n, int digits) {
- printFloat(n, digits);
+ // Enable TX ISR - Non atomic, but it will eventually enable TX ISR
+ B_UDRIE = 1;
}
+}
- template
- void MarlinSerial::println() {
- print('\r');
- print('\n');
- }
-
- template
- void MarlinSerial::println(const String& s) {
- print(s);
- println();
- }
-
- template
- void MarlinSerial::println(const char c[]) {
- print(c);
- println();
- }
+template
+void MarlinSerial::flushTX() {
- template
- void MarlinSerial::println(char c, int base) {
- print(c, base);
- println();
- }
+ if (Cfg::TX_SIZE == 0) {
+ // No bytes written, no need to flush. This special case is needed since there's
+ // no way to force the TXC (transmit complete) bit to 1 during initialization.
+ if (!_written) return;
- template
- void MarlinSerial::println(unsigned char b, int base) {
- print(b, base);
- println();
- }
+ // Wait until everything was transmitted
+ while (!B_TXC) sw_barrier();
- template
- void MarlinSerial::println(int n, int base) {
- print(n, base);
- println();
- }
+ // At this point nothing is queued anymore (DRIE is disabled) and
+ // the hardware finished transmission (TXC is set).
- template
- void MarlinSerial::println(unsigned int n, int base) {
- print(n, base);
- println();
}
+ else {
- template
- void MarlinSerial::println(long n, int base) {
- print(n, base);
- println();
- }
+ // No bytes written, no need to flush. This special case is needed since there's
+ // no way to force the TXC (transmit complete) bit to 1 during initialization.
+ if (!_written) return;
- template
- void MarlinSerial::println(unsigned long n, int base) {
- print(n, base);
- println();
- }
+ // If global interrupts are disabled (as the result of being called from an ISR)...
+ if (!ISRS_ENABLED()) {
- template
- void MarlinSerial::println(double n, int digits) {
- print(n, digits);
- println();
- }
+ // Wait until everything was transmitted - We must do polling, as interrupts are disabled
+ while (tx_buffer.head != tx_buffer.tail || !B_TXC) {
- // Private Methods
+ // If there is more space, send an extra character
+ if (B_UDRE) _tx_udr_empty_irq();
- template
- void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
- if (n) {
- unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
- int8_t i = 0;
- while (n) {
- buf[i++] = n % base;
- n /= base;
+ sw_barrier();
}
- while (i--)
- print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
- }
- else
- print('0');
- }
- template
- void MarlinSerial::printFloat(double number, uint8_t digits) {
- // Handle negative numbers
- if (number < 0.0) {
- print('-');
- number = -number;
}
-
- // Round correctly so that print(1.999, 2) prints as "2.00"
- double rounding = 0.5;
- LOOP_L_N(i, digits) rounding *= 0.1;
- number += rounding;
-
- // Extract the integer part of the number and print it
- unsigned long int_part = (unsigned long)number;
- double remainder = number - (double)int_part;
- print(int_part);
-
- // Print the decimal point, but only if there are digits beyond
- if (digits) {
- print('.');
- // Extract digits from the remainder one at a time
- while (digits--) {
- remainder *= 10.0;
- int toPrint = int(remainder);
- print(toPrint);
- remainder -= toPrint;
- }
+ else {
+ // Wait until everything was transmitted
+ while (tx_buffer.head != tx_buffer.tail || !B_TXC) sw_barrier();
}
- }
- // Hookup ISR handlers
- ISR(SERIAL_REGNAME(USART,SERIAL_PORT,_RX_vect)) {
- MarlinSerial>::store_rxd_char();
+ // At this point nothing is queued anymore (DRIE is disabled) and
+ // the hardware finished transmission (TXC is set).
}
+}
- ISR(SERIAL_REGNAME(USART,SERIAL_PORT,_UDRE_vect)) {
- MarlinSerial>::_tx_udr_empty_irq();
- }
-
- // Preinstantiate
- template class MarlinSerial>;
-
- // Instantiate
- MarlinSerial> customizedSerial1;
-
- #ifdef SERIAL_PORT_2
+/**
+ * Imports from print.h
+ */
- // Hookup ISR handlers
- ISR(SERIAL_REGNAME(USART,SERIAL_PORT_2,_RX_vect)) {
- MarlinSerial>::store_rxd_char();
+template
+void MarlinSerial::print(char c, int base) {
+ print((long)c, base);
+}
+
+template
+void MarlinSerial::print(unsigned char b, int base) {
+ print((unsigned long)b, base);
+}
+
+template
+void MarlinSerial::print(int n, int base) {
+ print((long)n, base);
+}
+
+template
+void MarlinSerial::print(unsigned int n, int base) {
+ print((unsigned long)n, base);
+}
+
+template
+void MarlinSerial::print(long n, int base) {
+ if (base == 0) write(n);
+ else if (base == 10) {
+ if (n < 0) { print('-'); n = -n; }
+ printNumber(n, 10);
+ }
+ else
+ printNumber(n, base);
+}
+
+template
+void MarlinSerial::print(unsigned long n, int base) {
+ if (base == 0) write(n);
+ else printNumber(n, base);
+}
+
+template
+void MarlinSerial::print(double n, int digits) {
+ printFloat(n, digits);
+}
+
+template
+void MarlinSerial::println() {
+ print('\r');
+ print('\n');
+}
+
+template
+void MarlinSerial::println(const String& s) {
+ print(s);
+ println();
+}
+
+template
+void MarlinSerial::println(const char c[]) {
+ print(c);
+ println();
+}
+
+template
+void MarlinSerial::println(char c, int base) {
+ print(c, base);
+ println();
+}
+
+template
+void MarlinSerial::println(unsigned char b, int base) {
+ print(b, base);
+ println();
+}
+
+template
+void MarlinSerial::println(int n, int base) {
+ print(n, base);
+ println();
+}
+
+template
+void MarlinSerial::println(unsigned int n, int base) {
+ print(n, base);
+ println();
+}
+
+template
+void MarlinSerial::println(long n, int base) {
+ print(n, base);
+ println();
+}
+
+template
+void MarlinSerial::println(unsigned long n, int base) {
+ print(n, base);
+ println();
+}
+
+template
+void MarlinSerial::println(double n, int digits) {
+ print(n, digits);
+ println();
+}
+
+// Private Methods
+
+template
+void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
+ if (n) {
+ unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
+ int8_t i = 0;
+ while (n) {
+ buf[i++] = n % base;
+ n /= base;
}
-
- ISR(SERIAL_REGNAME(USART,SERIAL_PORT_2,_UDRE_vect)) {
- MarlinSerial>::_tx_udr_empty_irq();
+ while (i--)
+ print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
+ }
+ else
+ print('0');
+}
+
+template
+void MarlinSerial::printFloat(double number, uint8_t digits) {
+ // Handle negative numbers
+ if (number < 0.0) {
+ print('-');
+ number = -number;
+ }
+
+ // Round correctly so that print(1.999, 2) prints as "2.00"
+ double rounding = 0.5;
+ LOOP_L_N(i, digits) rounding *= 0.1;
+ number += rounding;
+
+ // Extract the integer part of the number and print it
+ unsigned long int_part = (unsigned long)number;
+ double remainder = number - (double)int_part;
+ print(int_part);
+
+ // Print the decimal point, but only if there are digits beyond
+ if (digits) {
+ print('.');
+ // Extract digits from the remainder one at a time
+ while (digits--) {
+ remainder *= 10.0;
+ int toPrint = int(remainder);
+ print(toPrint);
+ remainder -= toPrint;
}
+ }
+}
- // Preinstantiate
- template class MarlinSerial>;
+// Hookup ISR handlers
+ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _RX_vect)) {
+ MarlinSerial>::store_rxd_char();
+}
- // Instantiate
- MarlinSerial> customizedSerial2;
+ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _UDRE_vect)) {
+ MarlinSerial>::_tx_udr_empty_irq();
+}
- #endif
+// Preinstantiate
+template class MarlinSerial>;
-#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
+// Instantiate
+MarlinSerial> customizedSerial1;
-#ifdef INTERNAL_SERIAL_PORT
+#ifdef SERIAL_PORT_2
- ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_RX_vect)) {
- MarlinSerial>::store_rxd_char();
+ // Hookup ISR handlers
+ ISR(SERIAL_REGNAME(USART, SERIAL_PORT_2, _RX_vect)) {
+ MarlinSerial>::store_rxd_char();
}
- ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_UDRE_vect)) {
- MarlinSerial>::_tx_udr_empty_irq();
+ ISR(SERIAL_REGNAME(USART, SERIAL_PORT_2, _UDRE_vect)) {
+ MarlinSerial>::_tx_udr_empty_irq();
}
// Preinstantiate
- template class MarlinSerial>;
+ template class MarlinSerial>;
// Instantiate
- MarlinSerial> internalSerial;
+ MarlinSerial> customizedSerial2;
#endif
-#ifdef DGUS_SERIAL_PORT
-
- 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.
- h = tx_buffer.head; // next pos for queue.
- int ret = t - h - 1;
- if (ret < 0) ret += Cfg::TX_SIZE + 1;
- return ret;
- }
+#ifdef MMU2_SERIAL_PORT
- ISR(SERIAL_REGNAME(USART,DGUS_SERIAL_PORT,_RX_vect)) {
- MarlinSerial>::store_rxd_char();
+ ISR(SERIAL_REGNAME(USART, MMU2_SERIAL_PORT, _RX_vect)) {
+ MarlinSerial>::store_rxd_char();
}
- ISR(SERIAL_REGNAME(USART,DGUS_SERIAL_PORT,_UDRE_vect)) {
- MarlinSerial>::_tx_udr_empty_irq();
+ ISR(SERIAL_REGNAME(USART, MMU2_SERIAL_PORT, _UDRE_vect)) {
+ MarlinSerial>::_tx_udr_empty_irq();
}
// Preinstantiate
- template class MarlinSerial>;
+ template class MarlinSerial>;
// Instantiate
- MarlinSerial> internalDgusSerial;
+ MarlinSerial> mmuSerial;
#endif
-#ifdef ANYCUBIC_LCD_SERIAL_PORT
+#ifdef LCD_SERIAL_PORT
- ISR(SERIAL_REGNAME(USART,ANYCUBIC_LCD_SERIAL_PORT,_RX_vect)) {
- MarlinSerial>::store_rxd_char();
+ ISR(SERIAL_REGNAME(USART, LCD_SERIAL_PORT, _RX_vect)) {
+ MarlinSerial>::store_rxd_char();
}
- ISR(SERIAL_REGNAME(USART,ANYCUBIC_LCD_SERIAL_PORT,_UDRE_vect)) {
- MarlinSerial>::_tx_udr_empty_irq();
+ ISR(SERIAL_REGNAME(USART, LCD_SERIAL_PORT, _UDRE_vect)) {
+ MarlinSerial>::_tx_udr_empty_irq();
}
// Preinstantiate
- template class MarlinSerial>;
+ template class MarlinSerial>;
// Instantiate
- MarlinSerial> anycubicLcdSerial;
+ MarlinSerial> lcdSerial;
+
+ #if HAS_DGUS_LCD
+ 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.
+ h = tx_buffer.head; // next pos for queue.
+ int ret = t - h - 1;
+ if (ret < 0) ret += Cfg::TX_SIZE + 1;
+ return ret;
+ }
+ #endif
#endif
+#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
+
// For AT90USB targets use the UART for BT interfacing
#if defined(USBCON) && ENABLED(BLUETOOTH)
HardwareSerial bluetoothSerial;
diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h
index e8bfc5583a91..8a0423d143d8 100644
--- a/Marlin/src/HAL/AVR/MarlinSerial.h
+++ b/Marlin/src/HAL/AVR/MarlinSerial.h
@@ -48,11 +48,11 @@
// These are macros to build serial port register names for the selected SERIAL_PORT (C preprocessor
// requires two levels of indirection to expand macro values properly)
- #define SERIAL_REGNAME(registerbase,number,suffix) SERIAL_REGNAME_INTERNAL(registerbase,number,suffix)
+ #define SERIAL_REGNAME(registerbase,number,suffix) _SERIAL_REGNAME(registerbase,number,suffix)
#if SERIAL_PORT == 0 && (!defined(UBRR0H) || !defined(UDR0)) // use un-numbered registers if necessary
- #define SERIAL_REGNAME_INTERNAL(registerbase,number,suffix) registerbase##suffix
+ #define _SERIAL_REGNAME(registerbase,number,suffix) registerbase##suffix
#else
- #define SERIAL_REGNAME_INTERNAL(registerbase,number,suffix) registerbase##number##suffix
+ #define _SERIAL_REGNAME(registerbase,number,suffix) registerbase##number##suffix
#endif
// Registers used by MarlinSerial class (expanded depending on selected serial port)
@@ -217,10 +217,12 @@
static ring_buffer_pos_t available();
static void write(const uint8_t c);
static void flushTX();
- #ifdef DGUS_SERIAL_PORT
+ #if HAS_DGUS_LCD
static ring_buffer_pos_t get_tx_buffer_free();
#endif
+ static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; }
+
FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; }
FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; }
FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; }
@@ -278,55 +280,50 @@
#endif // !USBCON
-#ifdef INTERNAL_SERIAL_PORT
+#ifdef MMU2_SERIAL_PORT
template
- struct MarlinInternalSerialCfg {
+ struct MMU2SerialCfg {
static constexpr int PORT = serial;
- static constexpr unsigned int RX_SIZE = 32;
- static constexpr unsigned int TX_SIZE = 32;
static constexpr bool XONOFF = false;
static constexpr bool EMERGENCYPARSER = false;
static constexpr bool DROPPED_RX = false;
- static constexpr bool RX_OVERRUNS = false;
static constexpr bool RX_FRAMING_ERRORS = false;
static constexpr bool MAX_RX_QUEUED = false;
+ static constexpr unsigned int RX_SIZE = 32;
+ static constexpr unsigned int TX_SIZE = 32;
+ static constexpr bool RX_OVERRUNS = false;
};
- extern MarlinSerial> internalSerial;
+ extern MarlinSerial> mmuSerial;
#endif
-#ifdef DGUS_SERIAL_PORT
- template
- struct MarlinInternalSerialCfg {
- static constexpr int PORT = serial;
- static constexpr unsigned int RX_SIZE = DGUS_RX_BUFFER_SIZE;
- static constexpr unsigned int TX_SIZE = DGUS_TX_BUFFER_SIZE;
- static constexpr bool XONOFF = false;
- static constexpr bool EMERGENCYPARSER = false;
- static constexpr bool DROPPED_RX = false;
- static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS);
- static constexpr bool RX_FRAMING_ERRORS = false;
- static constexpr bool MAX_RX_QUEUED = false;
- };
-
- extern MarlinSerial> internalDgusSerial;
-#endif
+#ifdef LCD_SERIAL_PORT
-#ifdef ANYCUBIC_LCD_SERIAL_PORT
template
- struct AnycubicLcdSerialCfg {
- static constexpr int PORT = serial;
- static constexpr unsigned int RX_SIZE = 64;
- static constexpr unsigned int TX_SIZE = 128;
- static constexpr bool XONOFF = false;
- static constexpr bool EMERGENCYPARSER = false;
- static constexpr bool DROPPED_RX = false;
- static constexpr bool RX_OVERRUNS = false;
- static constexpr bool RX_FRAMING_ERRORS = false;
- static constexpr bool MAX_RX_QUEUED = false;
+ struct LCDSerialCfg {
+ static constexpr int PORT = serial;
+ static constexpr bool XONOFF = false;
+ static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER);
+ static constexpr bool DROPPED_RX = false;
+ static constexpr bool RX_FRAMING_ERRORS = false;
+ static constexpr bool MAX_RX_QUEUED = false;
+ #if HAS_DGUS_LCD
+ static constexpr unsigned int RX_SIZE = DGUS_RX_BUFFER_SIZE;
+ static constexpr unsigned int TX_SIZE = DGUS_TX_BUFFER_SIZE;
+ static constexpr bool RX_OVERRUNS = ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS);
+ #elif EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON)
+ static constexpr unsigned int RX_SIZE = 64;
+ static constexpr unsigned int TX_SIZE = 128;
+ static constexpr bool RX_OVERRUNS = false;
+ #else
+ static constexpr unsigned int RX_SIZE = 64;
+ static constexpr unsigned int TX_SIZE = 128;
+ static constexpr bool RX_OVERRUNS = false
+ #endif
};
- extern MarlinSerial> anycubicLcdSerial;
+ extern MarlinSerial> lcdSerial;
+
#endif
// Use the UART for Bluetooth in AT90USB configurations
diff --git a/Marlin/src/HAL/AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp
index 66ed993c6f18..526352b77339 100644
--- a/Marlin/src/HAL/AVR/Servo.cpp
+++ b/Marlin/src/HAL/AVR/Servo.cpp
@@ -48,7 +48,6 @@
* readMicroseconds() - Get the last-written servo pulse width in microseconds.
* attached() - Return true if a servo is attached.
* detach() - Stop an attached servo from pulsing its i/o pin.
- *
*/
#ifdef __AVR__
diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp
index 29866bccf924..238c1124adeb 100644
--- a/Marlin/src/HAL/AVR/fast_pwm.cpp
+++ b/Marlin/src/HAL/AVR/fast_pwm.cpp
@@ -185,8 +185,8 @@ void set_pwm_frequency(const pin_t pin, int f_desired) {
res_temp_phase_correct = rtf / 2;
}
- LIMIT(res_temp_fast, 1u, size);
- LIMIT(res_temp_phase_correct, 1u, size);
+ LIMIT(res_temp_fast, 1U, size);
+ LIMIT(res_temp_phase_correct, 1U, size);
// Calculate frequencies of test prescaler and resolution values
const int f_temp_fast = (F_CPU) / (prescaler[i] * (1 + res_temp_fast)),
f_temp_phase_correct = (F_CPU) / (2 * prescaler[i] * res_temp_phase_correct),
diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h
index bd6935aaf0ce..dd0163466110 100644
--- a/Marlin/src/HAL/AVR/fastio.h
+++ b/Marlin/src/HAL/AVR/fastio.h
@@ -29,11 +29,17 @@
#include
-#define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__))
-#define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__))
-#define AVR_ATmega2560_FAMILY (defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__))
-#define AVR_ATmega2561_FAMILY (defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__))
-#define AVR_ATmega328_FAMILY (defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__))
+#if defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__)
+ #define AVR_AT90USB1286_FAMILY 1
+#elif defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__)
+ #define AVR_ATmega1284_FAMILY 1
+#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+ #define AVR_ATmega2560_FAMILY 1
+#elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
+ #define AVR_ATmega2561_FAMILY 1
+#elif defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__)
+ #define AVR_ATmega328_FAMILY 1
+#endif
/**
* Include Ports and Functions
diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h
index d73f520d1494..dac6b1b150bd 100644
--- a/Marlin/src/HAL/AVR/pinsDebug.h
+++ b/Marlin/src/HAL/AVR/pinsDebug.h
@@ -26,7 +26,9 @@
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
-#define AVR_ATmega2560_FAMILY_PLUS_70 MB(BQ_ZUM_MEGA_3D, MIGHTYBOARD_REVE, MINIRAMBO, SCOOVO_X9H)
+#if MB(BQ_ZUM_MEGA_3D, MIGHTYBOARD_REVE, MINIRAMBO, SCOOVO_X9H, TRIGORILLA_14)
+ #define AVR_ATmega2560_FAMILY_PLUS_70 1
+#endif
#if AVR_AT90USB1286_FAMILY
diff --git a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h
index 46c03088d213..db3fdf1f767b 100644
--- a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h
+++ b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h
@@ -22,15 +22,12 @@
* Structures for 2560 family boards that use more than 70 pins
*/
-#undef NUM_DIGITAL_PINS
-#if MB(BQ_ZUM_MEGA_3D)
+#if MB(BQ_ZUM_MEGA_3D, MINIRAMBO, SCOOVO_X9H, TRIGORILLA_14)
+ #undef NUM_DIGITAL_PINS
#define NUM_DIGITAL_PINS 85
#elif MB(MIGHTYBOARD_REVE)
+ #undef NUM_DIGITAL_PINS
#define NUM_DIGITAL_PINS 80
-#elif MB(MINIRAMBO)
- #define NUM_DIGITAL_PINS 85
-#elif MB(SCOOVO_X9H)
- #define NUM_DIGITAL_PINS 85
#endif
#define PA 1
diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h
index 6c40d3220924..82eb8b14b161 100644
--- a/Marlin/src/HAL/AVR/timers.h
+++ b/Marlin/src/HAL/AVR/timers.h
@@ -15,6 +15,7 @@
*
* 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/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp
index c29b19557899..cb95a48cccec 100644
--- a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp
+++ b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp
@@ -57,7 +57,7 @@
#include "../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD
+#if HAS_MARLINUI_U8GLIB
#include "../shared/Marduino.h"
#include "../shared/Delay.h"
@@ -189,5 +189,5 @@ uint8_t u8g_com_HAL_AVR_sw_sp_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void
return 1;
}
-#endif // HAS_GRAPHICAL_LCD
+#endif // HAS_MARLINUI_U8GLIB
#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp
index 4b9260c35962..6ce85a4643bb 100644
--- a/Marlin/src/HAL/DUE/HAL.cpp
+++ b/Marlin/src/HAL/DUE/HAL.cpp
@@ -19,9 +19,7 @@
*/
/**
- * Description: HAL for Arduino Due and compatible (SAM3X8E)
- *
- * For ARDUINO_ARCH_SAM
+ * HAL for Arduino Due and compatible (SAM3X8E)
*/
#ifdef ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h
index 31409c76dd56..88ace5957535 100644
--- a/Marlin/src/HAL/DUE/HAL.h
+++ b/Marlin/src/HAL/DUE/HAL.h
@@ -22,9 +22,7 @@
#pragma once
/**
- * Description: HAL for Arduino Due and compatible (SAM3X8E)
- *
- * For ARDUINO_ARCH_SAM
+ * HAL for Arduino Due and compatible (SAM3X8E)
*/
#define CPU_32_BIT
@@ -38,59 +36,36 @@
#include
+#define _MSERIAL(X) Serial##X
+#define MSERIAL(X) _MSERIAL(X)
+#define Serial0 Serial
+
// Define MYSERIAL0/1 before MarlinSerial includes!
#if SERIAL_PORT == -1 || ENABLED(EMERGENCY_PARSER)
#define MYSERIAL0 customizedSerial1
-#elif SERIAL_PORT == 0
- #define MYSERIAL0 Serial
-#elif SERIAL_PORT == 1
- #define MYSERIAL0 Serial1
-#elif SERIAL_PORT == 2
- #define MYSERIAL0 Serial2
-#elif SERIAL_PORT == 3
- #define MYSERIAL0 Serial3
+#elif WITHIN(SERIAL_PORT, 0, 3)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
#else
#error "The required SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
#ifdef SERIAL_PORT_2
- #if SERIAL_PORT_2 == SERIAL_PORT
- #error "SERIAL_PORT_2 must be different from SERIAL_PORT. Please update your configuration."
- #elif SERIAL_PORT_2 == -1 || ENABLED(EMERGENCY_PARSER)
+ #if SERIAL_PORT_2 == -1 || ENABLED(EMERGENCY_PARSER)
#define MYSERIAL1 customizedSerial2
- #elif SERIAL_PORT_2 == 0
- #define MYSERIAL1 Serial
- #elif SERIAL_PORT_2 == 1
- #define MYSERIAL1 Serial1
- #elif SERIAL_PORT_2 == 2
- #define MYSERIAL1 Serial2
- #elif SERIAL_PORT_2 == 3
- #define MYSERIAL1 Serial3
+ #elif WITHIN(SERIAL_PORT_2, 0, 3)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
#else
#error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
#endif
- #define NUM_SERIAL 2
-#else
- #define NUM_SERIAL 1
#endif
-#ifdef DGUS_SERIAL_PORT
- #if DGUS_SERIAL_PORT == SERIAL_PORT
- #error "DGUS_SERIAL_PORT must be different from SERIAL_PORT. Please update your configuration."
- #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
- #elif DGUS_SERIAL_PORT == -1
- #define DGUS_SERIAL internalDgusSerial
- #elif DGUS_SERIAL_PORT == 0
- #define DGUS_SERIAL Serial
- #elif DGUS_SERIAL_PORT == 1
- #define DGUS_SERIAL Serial1
- #elif DGUS_SERIAL_PORT == 2
- #define DGUS_SERIAL Serial2
- #elif DGUS_SERIAL_PORT == 3
- #define DGUS_SERIAL Serial3
+#ifdef LCD_SERIAL_PORT
+ #if LCD_SERIAL_PORT == -1
+ #define LCD_SERIAL lcdSerial
+ #elif WITHIN(LCD_SERIAL_PORT, 0, 3)
+ #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
- #error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
#endif
@@ -130,13 +105,15 @@ void sei(); // Enable interrupts
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
//
// ADC
//
extern uint16_t HAL_adc_result; // result of last ADC conversion
#ifndef analogInputToDigitalPin
- #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
+ #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define HAL_ANALOG_SELECT(ch)
diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp
index 6d8f7ef81939..0451d8bcc4ff 100644
--- a/Marlin/src/HAL/DUE/HAL_SPI.cpp
+++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp
@@ -30,7 +30,7 @@
*/
/**
- * Description: HAL for Arduino Due and compatible (SAM3X8E)
+ * HAL for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
*/
@@ -595,7 +595,7 @@
SPI_Enable(SPI0);
SET_OUTPUT(DAC0_SYNC);
- #if EXTRUDERS > 1
+ #if HAS_MULTI_EXTRUDER
SET_OUTPUT(DAC1_SYNC);
WRITE(DAC1_SYNC, HIGH);
#endif
@@ -759,7 +759,6 @@
*
* All of the above can be avoided by defining FORCE_SOFT_SPI to force the
* display to use software SPI.
- *
*/
void spiInit(uint8_t spiRate=6) { // Default to slowest rate if not specified)
diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h
index dfafa1514159..a194eba2f386 100644
--- a/Marlin/src/HAL/DUE/MarlinSerial.h
+++ b/Marlin/src/HAL/DUE/MarlinSerial.h
@@ -122,6 +122,8 @@ class MarlinSerial {
static void write(const uint8_t c);
static void flushTX();
+ static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; }
+
FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; }
FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; }
FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; }
diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp
index 28e82d70d454..be4b49c0f992 100644
--- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp
+++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp
@@ -52,14 +52,13 @@
* 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 __SAM3X8E__
#include "../../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD
+#if HAS_MARLINUI_U8GLIB
#include
@@ -145,6 +144,6 @@ uint8_t u8g_com_HAL_DUE_shared_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va
return 1;
}
-#endif // HAS_GRAPHICAL_LCD
+#endif // HAS_MARLINUI_U8GLIB
#endif // __SAM3X8E__
diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp
index 54c244d4f615..ea7204fa366b 100644
--- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp
+++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp
@@ -57,7 +57,7 @@
#include "../../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD && DISABLED(U8GLIB_ST7920)
+#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920)
#undef SPI_SPEED
#define SPI_SPEED 2 // About 2 MHz
@@ -144,5 +144,5 @@ uint8_t u8g_com_HAL_DUE_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void
return 1;
}
-#endif // HAS_GRAPHICAL_LCD && !U8GLIB_ST7920
+#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920
#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
index 960df1bd864b..615a386c3542 100644
--- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
+++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
@@ -57,7 +57,7 @@
#include "../../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD
+#if HAS_MARLINUI_U8GLIB
#include "../../shared/Delay.h"
@@ -108,5 +108,5 @@ void u8g_spiSend_sw_DUE_mode_3(uint8_t val) { // 3.5MHz
}
}
-#endif // HAS_GRAPHICAL_LCD
+#endif // HAS_MARLINUI_U8GLIB
#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp
index d98f06039f51..6f38da0967cb 100644
--- a/Marlin/src/HAL/DUE/eeprom_flash.cpp
+++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp
@@ -53,7 +53,6 @@
* per page. We can't emulate EE endurance with FLASH for all
* bytes, but we can emulate endurance for a given percent of
* bytes.
- *
*/
//#define EE_EMU_DEBUG
@@ -61,7 +60,7 @@
#define EEPROMSize 4096
#define PagesPerGroup 128
#define GroupCount 2
-#define PageSize 256u
+#define PageSize 256U
/* Flash storage */
typedef struct FLASH_SECTOR {
diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h
index 28687ff267c4..a99ca8ecce90 100644
--- a/Marlin/src/HAL/DUE/pinsDebug.h
+++ b/Marlin/src/HAL/DUE/pinsDebug.h
@@ -179,5 +179,4 @@ void pwm_details(int32_t pin) {
* ----------------+--------
* ID | PB11
* VBOF | PB10
- *
*/
diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp
index 795cdad66a57..9b937d1a7c83 100644
--- a/Marlin/src/HAL/DUE/timers.cpp
+++ b/Marlin/src/HAL/DUE/timers.cpp
@@ -21,9 +21,7 @@
*/
/**
- * Description: HAL for Arduino Due and compatible (SAM3X8E)
- *
- * For ARDUINO_ARCH_SAM
+ * HAL Timers for Arduino Due and compatible (SAM3X8E)
*/
#ifdef ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h
index 9defe39a0ae3..0e1ea07cc2e4 100644
--- a/Marlin/src/HAL/DUE/timers.h
+++ b/Marlin/src/HAL/DUE/timers.h
@@ -21,9 +21,7 @@
#pragma once
/**
- * HAL for Arduino Due and compatible (SAM3X8E)
- *
- * For ARDUINO_ARCH_SAM
+ * HAL Timers for Arduino Due and compatible (SAM3X8E)
*/
#include
diff --git a/Marlin/src/HAL/DUE/upload_extra_script.py b/Marlin/src/HAL/DUE/upload_extra_script.py
index 06c2b914f53d..d52a0a3642b4 100644
--- a/Marlin/src/HAL/DUE/upload_extra_script.py
+++ b/Marlin/src/HAL/DUE/upload_extra_script.py
@@ -14,5 +14,5 @@
# Use bossac.exe on Windows
env.Replace(
- UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot"
+ UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot $SOURCE"
)
diff --git a/Marlin/src/HAL/DUE/usb/compiler.h b/Marlin/src/HAL/DUE/usb/compiler.h
index 7b746543c4c6..f89e554c4562 100644
--- a/Marlin/src/HAL/DUE/usb/compiler.h
+++ b/Marlin/src/HAL/DUE/usb/compiler.h
@@ -173,11 +173,11 @@
# define __always_inline __forceinline
#elif (defined __GNUC__)
#ifdef __always_inline
-# undef __always_inline
+# undef __always_inline
#endif
-# define __always_inline inline __attribute__((__always_inline__))
+# define __always_inline inline __attribute__((__always_inline__))
#elif (defined __ICCARM__)
-# define __always_inline _Pragma("inline=forced")
+# define __always_inline _Pragma("inline=forced")
#endif
/**
@@ -188,11 +188,11 @@
* heuristics and not inline the function.
*/
#ifdef __CC_ARM
-# define __no_inline __attribute__((noinline))
+# define __no_inline __attribute__((noinline))
#elif (defined __GNUC__)
-# define __no_inline __attribute__((__noinline__))
+# define __no_inline __attribute__((__noinline__))
#elif (defined __ICCARM__)
-# define __no_inline _Pragma("inline=never")
+# define __no_inline _Pragma("inline=never")
#endif
/*! \brief This macro is used to test fatal errors.
@@ -211,9 +211,9 @@
# else
#undef TEST_SUITE_DEFINE_ASSERT_MACRO
# define Assert(expr) \
- {\
- if (!(expr)) while (true);\
- }
+ {\
+ if (!(expr)) while (true);\
+ }
# endif
#else
# define Assert(expr) ((void) 0)
@@ -609,37 +609,37 @@ typedef struct
# define clz(u) ((u) ? __CLZ(u) : 32)
#else
# define clz(u) (((u) == 0) ? 32 : \
- ((u) & (1ul << 31)) ? 0 : \
- ((u) & (1ul << 30)) ? 1 : \
- ((u) & (1ul << 29)) ? 2 : \
- ((u) & (1ul << 28)) ? 3 : \
- ((u) & (1ul << 27)) ? 4 : \
- ((u) & (1ul << 26)) ? 5 : \
- ((u) & (1ul << 25)) ? 6 : \
- ((u) & (1ul << 24)) ? 7 : \
- ((u) & (1ul << 23)) ? 8 : \
- ((u) & (1ul << 22)) ? 9 : \
- ((u) & (1ul << 21)) ? 10 : \
- ((u) & (1ul << 20)) ? 11 : \
- ((u) & (1ul << 19)) ? 12 : \
- ((u) & (1ul << 18)) ? 13 : \
- ((u) & (1ul << 17)) ? 14 : \
- ((u) & (1ul << 16)) ? 15 : \
- ((u) & (1ul << 15)) ? 16 : \
- ((u) & (1ul << 14)) ? 17 : \
- ((u) & (1ul << 13)) ? 18 : \
- ((u) & (1ul << 12)) ? 19 : \
- ((u) & (1ul << 11)) ? 20 : \
- ((u) & (1ul << 10)) ? 21 : \
- ((u) & (1ul << 9)) ? 22 : \
- ((u) & (1ul << 8)) ? 23 : \
- ((u) & (1ul << 7)) ? 24 : \
- ((u) & (1ul << 6)) ? 25 : \
- ((u) & (1ul << 5)) ? 26 : \
- ((u) & (1ul << 4)) ? 27 : \
- ((u) & (1ul << 3)) ? 28 : \
- ((u) & (1ul << 2)) ? 29 : \
- ((u) & (1ul << 1)) ? 30 : \
+ ((u) & (1UL << 31)) ? 0 : \
+ ((u) & (1UL << 30)) ? 1 : \
+ ((u) & (1UL << 29)) ? 2 : \
+ ((u) & (1UL << 28)) ? 3 : \
+ ((u) & (1UL << 27)) ? 4 : \
+ ((u) & (1UL << 26)) ? 5 : \
+ ((u) & (1UL << 25)) ? 6 : \
+ ((u) & (1UL << 24)) ? 7 : \
+ ((u) & (1UL << 23)) ? 8 : \
+ ((u) & (1UL << 22)) ? 9 : \
+ ((u) & (1UL << 21)) ? 10 : \
+ ((u) & (1UL << 20)) ? 11 : \
+ ((u) & (1UL << 19)) ? 12 : \
+ ((u) & (1UL << 18)) ? 13 : \
+ ((u) & (1UL << 17)) ? 14 : \
+ ((u) & (1UL << 16)) ? 15 : \
+ ((u) & (1UL << 15)) ? 16 : \
+ ((u) & (1UL << 14)) ? 17 : \
+ ((u) & (1UL << 13)) ? 18 : \
+ ((u) & (1UL << 12)) ? 19 : \
+ ((u) & (1UL << 11)) ? 20 : \
+ ((u) & (1UL << 10)) ? 21 : \
+ ((u) & (1UL << 9)) ? 22 : \
+ ((u) & (1UL << 8)) ? 23 : \
+ ((u) & (1UL << 7)) ? 24 : \
+ ((u) & (1UL << 6)) ? 25 : \
+ ((u) & (1UL << 5)) ? 26 : \
+ ((u) & (1UL << 4)) ? 27 : \
+ ((u) & (1UL << 3)) ? 28 : \
+ ((u) & (1UL << 2)) ? 29 : \
+ ((u) & (1UL << 1)) ? 30 : \
31)
#endif
#endif
@@ -654,38 +654,38 @@ typedef struct
#if (defined __GNUC__) || (defined __CC_ARM)
# define ctz(u) ((u) ? __builtin_ctz(u) : 32)
#else
-# define ctz(u) ((u) & (1ul << 0) ? 0 : \
- (u) & (1ul << 1) ? 1 : \
- (u) & (1ul << 2) ? 2 : \
- (u) & (1ul << 3) ? 3 : \
- (u) & (1ul << 4) ? 4 : \
- (u) & (1ul << 5) ? 5 : \
- (u) & (1ul << 6) ? 6 : \
- (u) & (1ul << 7) ? 7 : \
- (u) & (1ul << 8) ? 8 : \
- (u) & (1ul << 9) ? 9 : \
- (u) & (1ul << 10) ? 10 : \
- (u) & (1ul << 11) ? 11 : \
- (u) & (1ul << 12) ? 12 : \
- (u) & (1ul << 13) ? 13 : \
- (u) & (1ul << 14) ? 14 : \
- (u) & (1ul << 15) ? 15 : \
- (u) & (1ul << 16) ? 16 : \
- (u) & (1ul << 17) ? 17 : \
- (u) & (1ul << 18) ? 18 : \
- (u) & (1ul << 19) ? 19 : \
- (u) & (1ul << 20) ? 20 : \
- (u) & (1ul << 21) ? 21 : \
- (u) & (1ul << 22) ? 22 : \
- (u) & (1ul << 23) ? 23 : \
- (u) & (1ul << 24) ? 24 : \
- (u) & (1ul << 25) ? 25 : \
- (u) & (1ul << 26) ? 26 : \
- (u) & (1ul << 27) ? 27 : \
- (u) & (1ul << 28) ? 28 : \
- (u) & (1ul << 29) ? 29 : \
- (u) & (1ul << 30) ? 30 : \
- (u) & (1ul << 31) ? 31 : \
+# define ctz(u) ((u) & (1UL << 0) ? 0 : \
+ (u) & (1UL << 1) ? 1 : \
+ (u) & (1UL << 2) ? 2 : \
+ (u) & (1UL << 3) ? 3 : \
+ (u) & (1UL << 4) ? 4 : \
+ (u) & (1UL << 5) ? 5 : \
+ (u) & (1UL << 6) ? 6 : \
+ (u) & (1UL << 7) ? 7 : \
+ (u) & (1UL << 8) ? 8 : \
+ (u) & (1UL << 9) ? 9 : \
+ (u) & (1UL << 10) ? 10 : \
+ (u) & (1UL << 11) ? 11 : \
+ (u) & (1UL << 12) ? 12 : \
+ (u) & (1UL << 13) ? 13 : \
+ (u) & (1UL << 14) ? 14 : \
+ (u) & (1UL << 15) ? 15 : \
+ (u) & (1UL << 16) ? 16 : \
+ (u) & (1UL << 17) ? 17 : \
+ (u) & (1UL << 18) ? 18 : \
+ (u) & (1UL << 19) ? 19 : \
+ (u) & (1UL << 20) ? 20 : \
+ (u) & (1UL << 21) ? 21 : \
+ (u) & (1UL << 22) ? 22 : \
+ (u) & (1UL << 23) ? 23 : \
+ (u) & (1UL << 24) ? 24 : \
+ (u) & (1UL << 25) ? 25 : \
+ (u) & (1UL << 26) ? 26 : \
+ (u) & (1UL << 27) ? 27 : \
+ (u) & (1UL << 28) ? 28 : \
+ (u) & (1UL << 29) ? 29 : \
+ (u) & (1UL << 30) ? 30 : \
+ (u) & (1UL << 31) ? 31 : \
32)
#endif
#endif
@@ -1106,17 +1106,16 @@ static inline uint16_t convert_byte_array_to_16_bit(uint8_t *data)
/* Converts a 8 Byte array into a 32-Bit value */
static inline uint32_t convert_byte_array_to_32_bit(uint8_t *data)
{
- union
- {
- uint32_t u32;
- uint8_t u8[8];
- }long_addr;
- uint8_t index;
- for (index = 0; index < 4; index++)
- {
- long_addr.u8[index] = *data++;
- }
- return long_addr.u32;
+ union
+ {
+ uint32_t u32;
+ uint8_t u8[8];
+ }long_addr;
+ uint8_t index;
+ for (index = 0; index < 4; index++) {
+ long_addr.u8[index] = *data++;
+ }
+ return long_addr.u32;
}
/**
diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h
index c91f9efff0b9..ebc16c9525e7 100644
--- a/Marlin/src/HAL/ESP32/HAL.h
+++ b/Marlin/src/HAL/ESP32/HAL.h
@@ -15,11 +15,12 @@
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see .
+ *
*/
#pragma once
/**
- * Description: HAL for Espressif ESP32 WiFi
+ * HAL for Espressif ESP32 WiFi
*/
#define CPU_32_BIT
@@ -58,9 +59,6 @@ extern portMUX_TYPE spinlock;
#else
#define MYSERIAL1 webSocketSerial
#endif
- #define NUM_SERIAL 2
-#else
- #define NUM_SERIAL 1
#endif
#define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock)
@@ -98,6 +96,8 @@ void HAL_clear_reset_source();
// reset reason
uint8_t HAL_get_reset_source();
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
void _delay_ms(int delay);
#pragma GCC diagnostic push
@@ -157,14 +157,14 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) {
if (stop >= start) {
// no overflow, so only loop while in between start and stop:
- // 0x00000000 -----------------start****stop-- 0xffffffff
+ // 0x00000000 -----------------start****stop-- 0xFFFFFFFF
while (ccount >= start && ccount < stop) {
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (ccount) );
}
}
else {
// stop did overflow, so only loop while outside of stop and start:
- // 0x00000000 **stop-------------------start** 0xffffffff
+ // 0x00000000 **stop-------------------start** 0xFFFFFFFF
while (ccount >= start || ccount < stop) {
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (ccount) );
}
diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
index 533f873e4ffd..ca7f47a1f8bd 100644
--- a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
+++ b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
@@ -86,7 +86,7 @@ int RingBuffer::read() {
ring_buffer_pos_t RingBuffer::read(uint8_t *buffer) {
ring_buffer_pos_t len = available();
- for(ring_buffer_pos_t i = 0; read_index != write_index; i++) {
+ for (ring_buffer_pos_t i = 0; read_index != write_index; i++) {
buffer[i] = data[read_index];
read_index = NEXT_INDEX(read_index, size);
}
@@ -139,9 +139,8 @@ size_t WebSocketSerial::write(const uint8_t c) {
size_t WebSocketSerial::write(const uint8_t* buffer, size_t size) {
size_t written = 0;
- for(size_t i = 0; i < size; i++) {
+ for (size_t i = 0; i < size; i++)
written += write(buffer[i]);
- }
return written;
}
diff --git a/Marlin/src/HAL/ESP32/ota.h b/Marlin/src/HAL/ESP32/ota.h
index 7f9b237aa6e1..546ace82dbb8 100644
--- a/Marlin/src/HAL/ESP32/ota.h
+++ b/Marlin/src/HAL/ESP32/ota.h
@@ -15,6 +15,7 @@
*
* 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/HAL.h b/Marlin/src/HAL/HAL.h
index c7b7531442db..8b6a978d2103 100644
--- a/Marlin/src/HAL/HAL.h
+++ b/Marlin/src/HAL/HAL.h
@@ -25,6 +25,12 @@
#include HAL_PATH(.,HAL.h)
+#ifdef SERIAL_PORT_2
+ #define NUM_SERIAL 2
+#else
+ #define NUM_SERIAL 1
+#endif
+
#define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION)
#ifndef I2C_ADDRESS
diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h
index 96e121d9153e..2e545e03d6f3 100644
--- a/Marlin/src/HAL/LINUX/HAL.h
+++ b/Marlin/src/HAL/LINUX/HAL.h
@@ -62,7 +62,6 @@ uint8_t _getc();
extern HalSerial usb_serial;
#define MYSERIAL0 usb_serial
-#define NUM_SERIAL 1
#define ST7920_DELAY_1 DELAY_NS(600)
#define ST7920_DELAY_2 DELAY_NS(750)
@@ -102,6 +101,8 @@ uint16_t HAL_adc_get_result();
inline void HAL_clear_reset_source(void) {}
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
/* ---------------- Delay in cycles */
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
Clock::delayCycles(x);
diff --git a/Marlin/src/HAL/LINUX/include/serial.h b/Marlin/src/HAL/LINUX/include/serial.h
index 154e95aec262..e91624938978 100644
--- a/Marlin/src/HAL/LINUX/include/serial.h
+++ b/Marlin/src/HAL/LINUX/include/serial.h
@@ -33,7 +33,6 @@
* Generic RingBuffer
* T type of the buffer array
* S size of the buffer (must be power of 2)
- *
*/
template class RingBuffer {
public:
@@ -79,6 +78,7 @@ class HalSerial {
#if ENABLED(EMERGENCY_PARSER)
EmergencyParser::State emergency_state;
+ static inline bool emergency_parser_enabled() { return true; }
#endif
HalSerial() { host_connected = true; }
diff --git a/Marlin/src/HAL/LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp
index 4eeef318e7e7..481f059030b7 100644
--- a/Marlin/src/HAL/LINUX/main.cpp
+++ b/Marlin/src/HAL/LINUX/main.cpp
@@ -107,7 +107,7 @@ int main() {
std::thread write_serial (write_serial_thread);
std::thread read_serial (read_serial_thread);
- #if NUM_SERIAL > 0
+ #ifdef MYSERIAL0
MYSERIAL0.begin(BAUDRATE);
SERIAL_ECHOLNPGM("x86_64 Initialized");
SERIAL_FLUSHTX();
diff --git a/Marlin/src/HAL/LINUX/servo_private.h b/Marlin/src/HAL/LINUX/servo_private.h
index 122cfef3ea21..bcc8d2037f90 100644
--- a/Marlin/src/HAL/LINUX/servo_private.h
+++ b/Marlin/src/HAL/LINUX/servo_private.h
@@ -45,7 +45,6 @@
* Version 2 Copyright (c) 2009 Michael Margolis. All right reserved.
*
* The only modification was to update/delete macros to match the LPC176x.
- *
*/
#include
diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h
index a444196f04bb..01ba28e5b604 100644
--- a/Marlin/src/HAL/LINUX/spi_pins.h
+++ b/Marlin/src/HAL/LINUX/spi_pins.h
@@ -24,7 +24,7 @@
#include "../../core/macros.h"
#include "../../inc/MarlinConfigPre.h"
-#if BOTH(HAS_GRAPHICAL_LCD, SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN)
+#if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == 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
diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h
index 0153bacf42dd..cb637e715dda 100644
--- a/Marlin/src/HAL/LPC1768/HAL.h
+++ b/Marlin/src/HAL/LPC1768/HAL.h
@@ -63,58 +63,35 @@ extern "C" volatile uint32_t _millis;
#define ST7920_DELAY_3 DELAY_NS(750)
#endif
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
+#define MSerial0 MSerial
+
#if SERIAL_PORT == -1
#define MYSERIAL0 UsbSerial
-#elif SERIAL_PORT == 0
- #define MYSERIAL0 MSerial
-#elif SERIAL_PORT == 1
- #define MYSERIAL0 MSerial1
-#elif SERIAL_PORT == 2
- #define MYSERIAL0 MSerial2
-#elif SERIAL_PORT == 3
- #define MYSERIAL0 MSerial3
+#elif WITHIN(SERIAL_PORT, 0, 3)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
#else
#error "SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
#ifdef SERIAL_PORT_2
- #if SERIAL_PORT_2 == SERIAL_PORT
- #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration."
- #elif SERIAL_PORT_2 == -1
+ #if SERIAL_PORT_2 == -1
#define MYSERIAL1 UsbSerial
- #elif SERIAL_PORT_2 == 0
- #define MYSERIAL1 MSerial
- #elif SERIAL_PORT_2 == 1
- #define MYSERIAL1 MSerial1
- #elif SERIAL_PORT_2 == 2
- #define MYSERIAL1 MSerial2
- #elif SERIAL_PORT_2 == 3
- #define MYSERIAL1 MSerial3
+ #elif WITHIN(SERIAL_PORT_2, 0, 3)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
#else
#error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
#endif
- #define NUM_SERIAL 2
-#else
- #define NUM_SERIAL 1
#endif
-#ifdef DGUS_SERIAL_PORT
- #if DGUS_SERIAL_PORT == SERIAL_PORT
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
- #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
- #elif DGUS_SERIAL_PORT == -1
- #define DGUS_SERIAL UsbSerial
- #elif DGUS_SERIAL_PORT == 0
- #define DGUS_SERIAL MSerial
- #elif DGUS_SERIAL_PORT == 1
- #define DGUS_SERIAL MSerial1
- #elif DGUS_SERIAL_PORT == 2
- #define DGUS_SERIAL MSerial2
- #elif DGUS_SERIAL_PORT == 3
- #define DGUS_SERIAL MSerial3
+#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 "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
#endif
@@ -223,6 +200,8 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255,
void HAL_clear_reset_source(void);
uint8_t HAL_get_reset_source(void);
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
// Add strcmp_P if missing
#ifndef strcmp_P
#define strcmp_P(a, b) strcmp((a), (b))
diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
index e13f2d98cbb9..b3d2908ac93e 100644
--- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
+++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
@@ -39,10 +39,10 @@
* Some of the LCD interfaces/adapters result in the LCD SPI and the SD card
* 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.
+ * 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.
+ * 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
*/
@@ -170,34 +170,20 @@ static inline void waitSpiTxEnd(LPC_SSP_TypeDef *spi_d) {
while (SSP_GetStatus(spi_d, SSP_STAT_BUSY) == SET) { /* nada */ } // wait until BSY=0
}
+// Retain the pin init state of the SPI, to avoid init more than once,
+// even if more instances of SPIClass exist
+static bool spiInitialised[BOARD_NR_SPI] = { false };
+
SPIClass::SPIClass(uint8_t device) {
// Init things specific to each SPI device
// clock divider setup is a bit of hack, and needs to be improved at a later date.
- PINSEL_CFG_Type PinCfg; // data structure to hold init values
#if BOARD_NR_SPI >= 1
_settings[0].spi_d = LPC_SSP0;
_settings[0].dataMode = SPI_MODE0;
_settings[0].dataSize = DATA_SIZE_8BIT;
_settings[0].clock = SPI_CLOCK_MAX;
- // _settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock);
- PinCfg.Funcnum = 2;
- PinCfg.OpenDrain = 0;
- PinCfg.Pinmode = 0;
- PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_SCK_PIN);
- PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_SCK_PIN);
- PINSEL_ConfigPin(&PinCfg);
- SET_OUTPUT(BOARD_SPI1_SCK_PIN);
-
- PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_MISO_PIN);
- PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_MISO_PIN);
- PINSEL_ConfigPin(&PinCfg);
- SET_INPUT(BOARD_SPI1_MISO_PIN);
-
- PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_MOSI_PIN);
- PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_MOSI_PIN);
- PINSEL_ConfigPin(&PinCfg);
- SET_OUTPUT(BOARD_SPI1_MOSI_PIN);
+ //_settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock);
#endif
#if BOARD_NR_SPI >= 2
@@ -205,34 +191,53 @@ SPIClass::SPIClass(uint8_t device) {
_settings[1].dataMode = SPI_MODE0;
_settings[1].dataSize = DATA_SIZE_8BIT;
_settings[1].clock = SPI_CLOCK_MAX;
- // _settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock);
+ //_settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock);
+ #endif
+
+ setModule(device);
+
+ // Init the GPDMA controller
+ // TODO: call once in the constructor? or each time?
+ GPDMA_Init();
+}
+
+void SPIClass::begin() {
+ // Init the SPI pins in the first begin call
+ if ((_currentSetting->spi_d == LPC_SSP0 && spiInitialised[0] == false) ||
+ (_currentSetting->spi_d == LPC_SSP1 && spiInitialised[1] == false)) {
+ pin_t sck, miso, mosi;
+ if (_currentSetting->spi_d == LPC_SSP0) {
+ sck = BOARD_SPI1_SCK_PIN;
+ miso = BOARD_SPI1_MISO_PIN;
+ mosi = BOARD_SPI1_MOSI_PIN;
+ spiInitialised[0] = true;
+ }
+ else if (_currentSetting->spi_d == LPC_SSP1) {
+ sck = BOARD_SPI2_SCK_PIN;
+ miso = BOARD_SPI2_MISO_PIN;
+ mosi = BOARD_SPI2_MOSI_PIN;
+ spiInitialised[1] = true;
+ }
+ PINSEL_CFG_Type PinCfg; // data structure to hold init values
PinCfg.Funcnum = 2;
PinCfg.OpenDrain = 0;
PinCfg.Pinmode = 0;
- PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_SCK_PIN);
- PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_SCK_PIN);
+ PinCfg.Pinnum = LPC176x::pin_bit(sck);
+ PinCfg.Portnum = LPC176x::pin_port(sck);
PINSEL_ConfigPin(&PinCfg);
- SET_OUTPUT(BOARD_SPI2_SCK_PIN);
+ SET_OUTPUT(sck);
- PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_MISO_PIN);
- PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_MISO_PIN);
+ PinCfg.Pinnum = LPC176x::pin_bit(miso);
+ PinCfg.Portnum = LPC176x::pin_port(miso);
PINSEL_ConfigPin(&PinCfg);
- SET_INPUT(BOARD_SPI2_MISO_PIN);
+ SET_INPUT(miso);
- PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_MOSI_PIN);
- PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_MOSI_PIN);
+ PinCfg.Pinnum = LPC176x::pin_bit(mosi);
+ PinCfg.Portnum = LPC176x::pin_port(mosi);
PINSEL_ConfigPin(&PinCfg);
- SET_OUTPUT(BOARD_SPI2_MOSI_PIN);
- #endif
-
- setModule(device);
-
- /* Initialize GPDMA controller */
- //TODO: call once in the constructor? or each time?
- GPDMA_Init();
-}
+ SET_OUTPUT(mosi);
+ }
-void SPIClass::begin() {
updateSettings();
SSP_Cmd(_currentSetting->spi_d, ENABLE); // start SSP running
}
@@ -246,7 +251,7 @@ void SPIClass::beginTransaction(const SPISettings &cfg) {
}
uint8_t SPIClass::transfer(const uint16_t b) {
- /* send and receive a single byte */
+ // Send and receive a single byte
SSP_ReceiveData(_currentSetting->spi_d); // read any previous data
SSP_SendData(_currentSetting->spi_d, b);
waitSpiTxEnd(_currentSetting->spi_d); // wait for it to finish
@@ -254,8 +259,7 @@ uint8_t SPIClass::transfer(const uint16_t b) {
}
uint16_t SPIClass::transfer16(const uint16_t data) {
- return (transfer((data >> 8) & 0xFF) << 8)
- | (transfer(data & 0xFF) & 0xFF);
+ return (transfer((data >> 8) & 0xFF) << 8) | (transfer(data & 0xFF) & 0xFF);
}
void SPIClass::end() {
@@ -294,23 +298,23 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) {
// Enable dma on SPI
SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, ENABLE);
- // only increase memory if minc is true
+ // Only increase memory if minc is true
GPDMACfg.MemoryIncrease = (minc ? GPDMA_DMACCxControl_SI : 0);
// Setup channel with given parameter
GPDMA_Setup(&GPDMACfg);
- // enabled dma
+ // Enable DMA
GPDMA_ChannelCmd(0, ENABLE);
- // wait data transfer
+ // Wait for data transfer
while (!GPDMA_IntGetStatus(GPDMA_STAT_RAWINTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_RAWINTERR, 0)) { }
- // clear err and int
+ // Clear err and int
GPDMA_ClearIntPending (GPDMA_STATCLR_INTTC, 0);
GPDMA_ClearIntPending (GPDMA_STATCLR_INTERR, 0);
- // dma disable
+ // Disable DMA
GPDMA_ChannelCmd(0, DISABLE);
waitSpiTxEnd(_currentSetting->spi_d);
diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
index c3fb3bd0e4d2..5374e005d3da 100644
--- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
+++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
@@ -24,28 +24,28 @@
#include "../../inc/MarlinConfigPre.h"
#include "MarlinSerial.h"
-#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0) || (defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT == 0)
+#if USING_SERIAL_0
MarlinSerial MSerial(LPC_UART0);
extern "C" void UART0_IRQHandler() {
MSerial.IRQHandler();
}
#endif
-#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1
+#if USING_SERIAL_1
MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1);
extern "C" void UART1_IRQHandler() {
MSerial1.IRQHandler();
}
#endif
-#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2
+#if USING_SERIAL_2
MarlinSerial MSerial2(LPC_UART2);
extern "C" void UART2_IRQHandler() {
MSerial2.IRQHandler();
}
#endif
-#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3
+#if USING_SERIAL_3
MarlinSerial MSerial3(LPC_UART3);
extern "C" void UART3_IRQHandler() {
MSerial3.IRQHandler();
diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h
index 98ce73d377a6..8d6b64378a0a 100644
--- a/Marlin/src/HAL/LPC1768/MarlinSerial.h
+++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h
@@ -57,6 +57,7 @@ class MarlinSerial : public HardwareSerial {
}
EmergencyParser::State emergency_state;
+ static inline bool emergency_parser_enabled() { return true; }
#endif
};
diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h
index e953cb920475..eb12fd20f4d8 100644
--- a/Marlin/src/HAL/LPC1768/Servo.h
+++ b/Marlin/src/HAL/LPC1768/Servo.h
@@ -46,7 +46,6 @@
* Version 2 Copyright (c) 2009 Michael Margolis. All right reserved.
*
* The only modification was to update/delete macros to match the LPC176x.
- *
*/
#include
diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
index caec347bf599..fd82e2884ae9 100644
--- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
+++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
@@ -89,7 +89,10 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
* Serial2 | P0_10 | P0_11 |
* Serial3 | P0_00 | P0_01 |
*/
-#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0) || (defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT == 0)
+#define ANY_TX(N,V...) DO(IS_TX##N,||,V)
+#define ANY_RX(N,V...) DO(IS_RX##N,||,V)
+
+#if USING_SERIAL_0
#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)
@@ -103,60 +106,67 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#undef IS_RX0
#endif
-#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1
+#if USING_SERIAL_1
#define IS_TX1(P) (P == P0_15)
#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)
#error "Serial port pins (1) conflict with other pins!"
- #elif HAS_SPI_LCD
+ #elif HAS_WIRED_LCD
#if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1)
#error "Serial port pins (1) conflict with Encoder Buttons!"
- #elif IS_TX1(SCK_PIN) || IS_TX1(LCD_PINS_D4) || IS_TX1(DOGLCD_SCK) || IS_TX1(LCD_RESET_PIN) || IS_TX1(LCD_PINS_RS) || IS_TX1(SHIFT_CLK) \
- || IS_RX1(LCD_SDSS) || IS_RX1(LCD_PINS_RS) || IS_RX1(MISO_PIN) || IS_RX1(DOGLCD_A0) || IS_RX1(SS_PIN) || IS_RX1(LCD_SDSS) || IS_RX1(DOGLCD_CS) || IS_RX1(LCD_RESET_PIN) || IS_RX1(LCD_BACKLIGHT_PIN)
+ #elif ANY_TX(1, SCK_PIN, LCD_PINS_D4, DOGLCD_SCK, LCD_RESET_PIN, LCD_PINS_RS, SHIFT_CLK) \
+ || ANY_RX(1, LCD_SDSS, LCD_PINS_RS, MISO_PIN, DOGLCD_A0, SS_PIN, LCD_SDSS, DOGLCD_CS, LCD_RESET_PIN, LCD_BACKLIGHT_PIN)
#error "Serial port pins (1) conflict with LCD pins!"
#endif
#endif
#undef IS_TX1
#undef IS_RX1
+ #undef _IS_TX1_1
+ #undef _IS_RX1_1
#endif
-#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2
+#if USING_SERIAL_2
#define IS_TX2(P) (P == P0_10)
#define IS_RX2(P) (P == P0_11)
- #if IS_TX2(X2_ENABLE_PIN) || IS_RX2(X2_DIR_PIN) || IS_RX2(X2_STEP_PIN) || (AXIS_HAS_SPI(X2) && IS_TX2(X2_CS_PIN))
+ #define _IS_TX2_1 IS_TX2
+ #define _IS_RX2_1 IS_RX2
+ #if IS_TX2(X2_ENABLE_PIN) || ANY_RX(2, X2_DIR_PIN, X2_STEP_PIN) || (AXIS_HAS_SPI(X2) && IS_TX2(X2_CS_PIN))
#error "Serial port pins (2) conflict with X2 pins!"
- #elif IS_TX2(Y2_ENABLE_PIN) || IS_RX2(Y2_DIR_PIN) || IS_RX2(Y2_STEP_PIN) || (AXIS_HAS_SPI(Y2) && IS_TX2(Y2_CS_PIN))
+ #elif IS_TX2(Y2_ENABLE_PIN) || ANY_RX(2, Y2_DIR_PIN, Y2_STEP_PIN) || (AXIS_HAS_SPI(Y2) && IS_TX2(Y2_CS_PIN))
#error "Serial port pins (2) conflict with Y2 pins!"
- #elif IS_TX2(Z2_ENABLE_PIN) || IS_RX2(Z2_DIR_PIN) || IS_RX2(Z2_STEP_PIN) || (AXIS_HAS_SPI(Z2) && IS_TX2(Z2_CS_PIN))
+ #elif IS_TX2(Z2_ENABLE_PIN) || ANY_RX(2, Z2_DIR_PIN, Z2_STEP_PIN) || (AXIS_HAS_SPI(Z2) && IS_TX2(Z2_CS_PIN))
#error "Serial port pins (2) conflict with Z2 pins!"
- #elif IS_TX2(Z3_ENABLE_PIN) || IS_RX2(Z3_DIR_PIN) || IS_RX2(Z3_STEP_PIN) || (AXIS_HAS_SPI(Z3) && IS_TX2(Z3_CS_PIN))
+ #elif IS_TX2(Z3_ENABLE_PIN) || ANY_RX(2, Z3_DIR_PIN, Z3_STEP_PIN) || (AXIS_HAS_SPI(Z3) && IS_TX2(Z3_CS_PIN))
#error "Serial port pins (2) conflict with Z3 pins!"
- #elif IS_TX2(Z4_ENABLE_PIN) || IS_RX2(Z4_DIR_PIN) || IS_RX2(Z4_STEP_PIN) || (AXIS_HAS_SPI(Z4) && IS_TX2(Z4_CS_PIN))
+ #elif IS_TX2(Z4_ENABLE_PIN) || ANY_RX(2, Z4_DIR_PIN, Z4_STEP_PIN) || (AXIS_HAS_SPI(Z4) && IS_TX2(Z4_CS_PIN))
#error "Serial port pins (2) conflict with Z4 pins!"
- #elif IS_RX2(X_DIR_PIN) || IS_RX2(Y_DIR_PIN)
+ #elif ANY_RX(2, X_DIR_PIN, Y_DIR_PIN)
#error "Serial port pins (2) conflict with other pins!"
#elif Y_HOME_DIR < 0 && IS_TX2(Y_STOP_PIN)
#error "Serial port pins (2) conflict with Y endstop pin!"
#elif HAS_CUSTOM_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN)
#error "Serial port pins (2) conflict with probe pin!"
- #elif IS_TX2(X_ENABLE_PIN) || IS_RX2(X_DIR_PIN) || IS_TX2(Y_ENABLE_PIN) || IS_RX2(Y_DIR_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!"
- #elif EXTRUDERS > 1 && (IS_TX2(E1_ENABLE_PIN) || (AXIS_HAS_SPI(E1) && IS_TX2(E1_CS_PIN)))
+ #elif HAS_MULTI_EXTRUDER && (IS_TX2(E1_ENABLE_PIN) || (AXIS_HAS_SPI(E1) && IS_TX2(E1_CS_PIN)))
#error "Serial port pins (2) conflict with E1 stepper pins!"
- #elif EXTRUDERS && (IS_RX2(E0_DIR_PIN) || IS_RX2(E0_STEP_PIN))
+ #elif EXTRUDERS && ANY_RX(2, E0_DIR_PIN, E0_STEP_PIN)
#error "Serial port pins (2) conflict with E stepper pins!"
#endif
#undef IS_TX2
#undef IS_RX2
+ #undef _IS_TX2_1
+ #undef _IS_RX2_1
#endif
-#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3
+#if USING_SERIAL_3
#define PIN_IS_TX3(P) (PIN_EXISTS(P) && P##_PIN == P0_00)
#define PIN_IS_RX3(P) (P##_PIN == P0_01)
#if PIN_IS_TX3(X_MIN) || PIN_IS_RX3(X_MAX)
#error "Serial port pins (3) conflict with X endstop pins!"
- #elif PIN_IS_TX3(Y_SERIAL_TX) || PIN_IS_TX3(Y_SERIAL_RX) \
- || PIN_IS_RX3(X_SERIAL_TX) || PIN_IS_RX3(X_SERIAL_RX)
+ #elif PIN_IS_TX3(Y_SERIAL_TX) || PIN_IS_TX3(Y_SERIAL_RX) || PIN_IS_RX3(X_SERIAL_TX) || PIN_IS_RX3(X_SERIAL_RX)
#error "Serial port pins (3) conflict with X/Y axis UART pins!"
#elif PIN_IS_TX3(X2_DIR) || PIN_IS_RX3(X2_STEP)
#error "Serial port pins (3) conflict with X2 pins!"
@@ -168,13 +178,16 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#error "Serial port pins (3) conflict with Z3 pins!"
#elif PIN_IS_TX3(Z4_DIR) || PIN_IS_RX3(Z4_STEP)
#error "Serial port pins (3) conflict with Z4 pins!"
- #elif EXTRUDERS > 1 && (PIN_IS_TX3(E1_DIR) || PIN_IS_RX3(E1_STEP))
+ #elif HAS_MULTI_EXTRUDER && (PIN_IS_TX3(E1_DIR) || PIN_IS_RX3(E1_STEP))
#error "Serial port pins (3) conflict with E1 pins!"
#endif
#undef PIN_IS_TX3
#undef PIN_IS_RX3
#endif
+#undef ANY_TX
+#undef ANY_RX
+
//
// Flag any i2c pin conflicts
//
@@ -214,7 +227,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#error "One or more i2c (1) pins overlaps with Z3 pins! Disable i2c peripherals."
#elif PIN_IS_SDA1(Z4_DIR) || PIN_IS_SCL1(Z4_STEP)
#error "One or more i2c (1) pins overlaps with Z4 pins! Disable i2c peripherals."
- #elif EXTRUDERS > 1 && (PIN_IS_SDA1(E1_DIR) || PIN_IS_SCL1(E1_STEP))
+ #elif HAS_MULTI_EXTRUDER && (PIN_IS_SDA1(E1_DIR) || PIN_IS_SCL1(E1_STEP))
#error "One or more i2c (1) pins overlaps with E1 pins! Disable i2c peripherals."
#endif
#undef PIN_IS_SDA1
@@ -240,9 +253,9 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#error "i2c SDA2 overlaps with Z3 enable pin! Disable i2c peripherals."
#elif PIN_IS_SDA2(Z4_ENABLE)
#error "i2c SDA2 overlaps with Z4 enable pin! Disable i2c peripherals."
- #elif EXTRUDERS > 1 && PIN_IS_SDA2(E1_ENABLE)
+ #elif HAS_MULTI_EXTRUDER && PIN_IS_SDA2(E1_ENABLE)
#error "i2c SDA2 overlaps with E1 enable pin! Disable i2c peripherals."
- #elif EXTRUDERS > 1 && AXIS_HAS_SPI(E1) && PIN_IS_SDA2(E1_CS)
+ #elif HAS_MULTI_EXTRUDER && AXIS_HAS_SPI(E1) && PIN_IS_SDA2(E1_CS)
#error "i2c SDA2 overlaps with E1 CS pin! Disable i2c peripherals."
#elif EXTRUDERS && (PIN_IS_SDA2(E0_STEP) || PIN_IS_SDA2(E0_DIR))
#error "i2c SCL2 overlaps with E0 STEP/DIR pin! Disable i2c peripherals."
diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h
index 2e6749bf5752..b4da5d4df234 100644
--- a/Marlin/src/HAL/LPC1768/spi_pins.h
+++ b/Marlin/src/HAL/LPC1768/spi_pins.h
@@ -23,7 +23,7 @@
#include "../../core/macros.h"
-#if BOTH(SDSUPPORT, HAS_GRAPHICAL_LCD) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN)
+#if BOTH(SDSUPPORT, HAS_MARLINUI_U8GLIB) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == 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
diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h
index 23dc20e2eb4e..e6744fb005bf 100644
--- a/Marlin/src/HAL/LPC1768/timers.h
+++ b/Marlin/src/HAL/LPC1768/timers.h
@@ -21,7 +21,6 @@
#pragma once
/**
- *
* HAL For LPC1768
*/
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 befc348fab49..057e10e0f545 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
@@ -57,7 +57,7 @@
#include "../../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD
+#if HAS_MARLINUI_U8GLIB
#include
#include "../../shared/HAL_SPI.h"
@@ -124,6 +124,6 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val,
return 1;
}
-#endif // HAS_GRAPHICAL_LCD
+#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 f03be9ab34dc..6f7efba4ae20 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
@@ -77,7 +77,7 @@
#include "../../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD
+#if HAS_MARLINUI_U8GLIB
#include
@@ -193,6 +193,6 @@ uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_v
return 1;
}
-#endif // HAS_GRAPHICAL_LCD
+#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 1500c22a0d52..592e27f6c006 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
@@ -57,7 +57,7 @@
#include "../../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD
+#if HAS_MARLINUI_U8GLIB
#include
#include "../../shared/HAL_SPI.h"
@@ -133,6 +133,6 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar
return 1;
}
-#endif // HAS_GRAPHICAL_LCD
+#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 4f52f7dd0129..ca9d6ecfbe25 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
@@ -57,7 +57,7 @@
#include "../../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD && DISABLED(U8GLIB_ST7920)
+#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920)
#include
@@ -203,5 +203,5 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val,
return 1;
}
-#endif // HAS_GRAPHICAL_LCD && !U8GLIB_ST7920
+#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920
#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/usb_serial.cpp b/Marlin/src/HAL/LPC1768/usb_serial.cpp
index 63a570efdfa8..d225ce418860 100644
--- a/Marlin/src/HAL/LPC1768/usb_serial.cpp
+++ b/Marlin/src/HAL/LPC1768/usb_serial.cpp
@@ -26,7 +26,9 @@
#if ENABLED(EMERGENCY_PARSER)
#include "../../feature/e_parser.h"
+
EmergencyParser::State emergency_state;
+
bool CDC_RecvCallback(const char buffer) {
emergency_parser.update(emergency_state, buffer);
return true;
diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h
index ea0f694cdc02..abc6c04a693b 100644
--- a/Marlin/src/HAL/SAMD51/HAL.h
+++ b/Marlin/src/HAL/SAMD51/HAL.h
@@ -35,58 +35,34 @@
// MYSERIAL0 required before MarlinSerial includes!
+ #define _MSERIAL(X) Serial##X
+ #define MSERIAL(X) _MSERIAL(INCREMENT(X))
+
#if SERIAL_PORT == -1
#define MYSERIAL0 Serial
- #elif SERIAL_PORT == 0
- #define MYSERIAL0 Serial1
- #elif SERIAL_PORT == 1
- #define MYSERIAL0 Serial2
- #elif SERIAL_PORT == 2
- #define MYSERIAL0 Serial3
- #elif SERIAL_PORT == 3
- #define MYSERIAL0 Serial4
+ #elif WITHIN(SERIAL_PORT, 0, 3)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
#else
#error "SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
#ifdef SERIAL_PORT_2
- #if SERIAL_PORT_2 == SERIAL_PORT
- #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration."
- #elif SERIAL_PORT_2 == -1
+ #if SERIAL_PORT_2 == -1
#define MYSERIAL1 Serial
- #elif SERIAL_PORT_2 == 0
- #define MYSERIAL1 Serial1
- #elif SERIAL_PORT_2 == 1
- #define MYSERIAL1 Serial2
- #elif SERIAL_PORT_2 == 2
- #define MYSERIAL1 Serial3
- #elif SERIAL_PORT_2 == 3
- #define MYSERIAL1 Serial4
+ #elif WITHIN(SERIAL_PORT_2, 0, 3)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
#else
#error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
#endif
- #define NUM_SERIAL 2
- #else
- #define NUM_SERIAL 1
#endif
- #ifdef DGUS_SERIAL_PORT
- #if DGUS_SERIAL_PORT == SERIAL_PORT
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
- #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
- #elif DGUS_SERIAL_PORT == -1
- #define DGUS_SERIAL Serial
- #elif DGUS_SERIAL_PORT == 0
- #define DGUS_SERIAL Serial1
- #elif DGUS_SERIAL_PORT == 1
- #define DGUS_SERIAL Serial2
- #elif DGUS_SERIAL_PORT == 2
- #define DGUS_SERIAL Serial3
- #elif DGUS_SERIAL_PORT == 2
- #define DGUS_SERIAL Serial4
+ #ifdef LCD_SERIAL_PORT
+ #if LCD_SERIAL_PORT == -1
+ #define LCD_SERIAL Serial
+ #elif WITHIN(LCD_SERIAL_PORT, 0, 3)
+ #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
- #error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
#endif
@@ -112,6 +88,8 @@ typedef int8_t pin_t;
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
//
// ADC
//
diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp
index 161c04084f36..307eb3fd45f2 100644
--- a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp
+++ b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp
@@ -26,7 +26,7 @@
#include "QSPIFlash.h"
-#define INVALID_ADDR 0xffffffff
+#define INVALID_ADDR 0xFFFFFFFF
#define SECTOR_OF(a) (a & ~(SFLASH_SECTOR_SIZE - 1))
#define OFFSET_OF(a) (a & (SFLASH_SECTOR_SIZE - 1))
diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD51/QSPIFlash.h
index b6f22769ff60..db4abec91caf 100644
--- a/Marlin/src/HAL/SAMD51/QSPIFlash.h
+++ b/Marlin/src/HAL/SAMD51/QSPIFlash.h
@@ -24,7 +24,6 @@
* THE SOFTWARE.
*
* Derived from Adafruit_SPIFlash class with no SdFat references
- *
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/pinsDebug.h b/Marlin/src/HAL/SAMD51/pinsDebug.h
index c28937d6c6d6..81376db79add 100644
--- a/Marlin/src/HAL/SAMD51/pinsDebug.h
+++ b/Marlin/src/HAL/SAMD51/pinsDebug.h
@@ -150,5 +150,4 @@ void pwm_details(int32_t pin) {
* 93 | PA10 | QSPI: IO2
* 94 | PA11 | QSPI: IO3
* 95 | PB31 | SD: DETECT
- *
*/
diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp
index b1b727ce195b..83604b1104bb 100644
--- a/Marlin/src/HAL/STM32/HAL.cpp
+++ b/Marlin/src/HAL/STM32/HAL.cpp
@@ -63,7 +63,7 @@ uint16_t HAL_adc_result;
void HAL_init() {
FastIO_init();
- #if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT)
+ #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
#endif
@@ -122,9 +122,14 @@ extern "C" {
// TODO: Make sure this doesn't cause any delay
void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
-
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
+// Reset the system (to initiate a firmware flash)
void flashFirmware(const int16_t) { NVIC_SystemReset(); }
+// Maple Compatibility
+systickCallback_t systick_user_callback;
+void systick_attach_callback(systickCallback_t cb) { systick_user_callback = cb; }
+void HAL_SYSTICK_Callback() { if (systick_user_callback) systick_user_callback(); }
+
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h
index 08081331b736..a1f7515d6b98 100644
--- a/Marlin/src/HAL/STM32/HAL.h
+++ b/Marlin/src/HAL/STM32/HAL.h
@@ -43,83 +43,40 @@
// ------------------------
// Defines
// ------------------------
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
-#if SERIAL_PORT == 0
- #error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
-#elif SERIAL_PORT == -1
+#if SERIAL_PORT == -1
#define MYSERIAL0 SerialUSB
-#elif SERIAL_PORT == 1
- #define MYSERIAL0 MSerial1
-#elif SERIAL_PORT == 2
- #define MYSERIAL0 MSerial2
-#elif SERIAL_PORT == 3
- #define MYSERIAL0 MSerial3
-#elif SERIAL_PORT == 4
- #define MYSERIAL0 MSerial4
-#elif SERIAL_PORT == 5
- #define MYSERIAL0 MSerial5
-#elif SERIAL_PORT == 6
- #define MYSERIAL0 MSerial6
+#elif WITHIN(SERIAL_PORT, 1, 6)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
#else
- #error "SERIAL_PORT must be from -1 to 6. Please update your configuration."
+ #error "SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration."
#endif
#ifdef SERIAL_PORT_2
- #define NUM_SERIAL 2
- #if SERIAL_PORT_2 == 0
- #error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration."
- #elif SERIAL_PORT_2 == SERIAL_PORT
- #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration."
- #elif SERIAL_PORT_2 == -1
+ #if SERIAL_PORT_2 == -1
#define MYSERIAL1 SerialUSB
- #elif SERIAL_PORT_2 == 1
- #define MYSERIAL1 MSerial1
- #elif SERIAL_PORT_2 == 2
- #define MYSERIAL1 MSerial2
- #elif SERIAL_PORT_2 == 3
- #define MYSERIAL1 MSerial3
- #elif SERIAL_PORT_2 == 4
- #define MYSERIAL1 MSerial4
- #elif SERIAL_PORT_2 == 5
- #define MYSERIAL1 MSerial5
- #elif SERIAL_PORT_2 == 6
- #define MYSERIAL1 MSerial6
+ #elif WITHIN(SERIAL_PORT_2, 1, 6)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
#else
- #error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration."
+ #error "SERIAL_PORT_2 must be -1 or from 1 to 6. Please update your configuration."
#endif
-#else
- #define NUM_SERIAL 1
#endif
-#if HAS_DGUS_LCD
- #if DGUS_SERIAL_PORT == 0
- #error "DGUS_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
- #elif DGUS_SERIAL_PORT == SERIAL_PORT
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
- #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
- #elif DGUS_SERIAL_PORT == -1
- #define DGUS_SERIAL SerialUSB
- #elif DGUS_SERIAL_PORT == 1
- #define DGUS_SERIAL MSerial1
- #elif DGUS_SERIAL_PORT == 2
- #define DGUS_SERIAL MSerial2
- #elif DGUS_SERIAL_PORT == 3
- #define DGUS_SERIAL MSerial3
- #elif DGUS_SERIAL_PORT == 4
- #define DGUS_SERIAL MSerial4
- #elif DGUS_SERIAL_PORT == 5
- #define DGUS_SERIAL MSerial5
- #elif DGUS_SERIAL_PORT == 6
- #define DGUS_SERIAL MSerial6
+#ifdef LCD_SERIAL_PORT
+ #if LCD_SERIAL_PORT == -1
+ #define LCD_SERIAL SerialUSB
+ #elif WITHIN(LCD_SERIAL_PORT, 1, 6)
+ #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
- #error "DGUS_SERIAL_PORT must be from -1 to 6. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration."
+ #endif
+ #if HAS_DGUS_LCD
+ #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#endif
-
- #define DGUS_SERIAL_GET_TX_BUFFER_FREE DGUS_SERIAL.availableForWrite
#endif
-
/**
* TODO: review this to return 1 for pins that are not analog input
*/
@@ -177,6 +134,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
void _delay_ms(const int delay);
extern "C" char* _sbrk(int incr);
@@ -220,3 +179,8 @@ uint16_t HAL_adc_get_result();
#define PLATFORM_M997_SUPPORT
void flashFirmware(const int16_t);
+
+// Maple Compatibility
+typedef void (*systickCallback_t)(void);
+void systick_attach_callback(systickCallback_t cb);
+void HAL_SYSTICK_Callback();
diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp
index 202442a71b00..f947e6ef3272 100644
--- a/Marlin/src/HAL/STM32/HAL_SPI.cpp
+++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp
@@ -132,11 +132,9 @@ static SPISettings spiConfig;
* @details Only configures SS pin since stm32duino creates and initialize the SPI object
*/
void spiBegin() {
- #if !PIN_EXISTS(SS)
- #error "SS_PIN not defined!"
+ #if PIN_EXISTS(SS)
+ OUT_WRITE(SS_PIN, HIGH);
#endif
-
- OUT_WRITE(SS_PIN, HIGH);
}
// Configure SPI for specified SPI speed
@@ -173,9 +171,7 @@ static SPISettings spiConfig;
* @details
*/
uint8_t spiRec() {
- SPI.beginTransaction(spiConfig);
uint8_t returnByte = SPI.transfer(0xFF);
- SPI.endTransaction();
return returnByte;
}
@@ -191,9 +187,7 @@ static SPISettings spiConfig;
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();
}
/**
@@ -204,9 +198,7 @@ static SPISettings spiConfig;
* @details
*/
void spiSend(uint8_t b) {
- SPI.beginTransaction(spiConfig);
SPI.transfer(b);
- SPI.endTransaction();
}
/**
@@ -219,10 +211,8 @@ static SPISettings spiConfig;
*/
void spiSendBlock(uint8_t token, const uint8_t* buf) {
uint8_t rxBuf[512];
- SPI.beginTransaction(spiConfig);
SPI.transfer(token);
SPI.transfer((uint8_t*)buf, &rxBuf, 512);
- SPI.endTransaction();
}
#endif // SOFTWARE_SPI
diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp
index 2d799ea54db0..a146664366df 100644
--- a/Marlin/src/HAL/STM32/MarlinSerial.cpp
+++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp
@@ -49,8 +49,8 @@
DECLARE_SERIAL_PORT_EXP(SERIAL_PORT_2)
#endif
-#if defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT >= 0
- DECLARE_SERIAL_PORT_EXP(DGUS_SERIAL_PORT)
+#if defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT >= 0
+ DECLARE_SERIAL_PORT_EXP(LCD_SERIAL_PORT)
#endif
void MarlinSerial::begin(unsigned long baud, uint8_t config) {
diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h
index 5ab97ff3a993..3611cc78d7ce 100644
--- a/Marlin/src/HAL/STM32/MarlinSerial.h
+++ b/Marlin/src/HAL/STM32/MarlinSerial.h
@@ -35,6 +35,10 @@ class MarlinSerial : public HardwareSerial {
#endif
{ }
+ #if ENABLED(EMERGENCY_PARSER)
+ static inline bool emergency_parser_enabled() { return true; }
+ #endif
+
void begin(unsigned long baud, uint8_t config);
inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); }
diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h
index d90b2fbeb02d..f000d68cf0c3 100644
--- a/Marlin/src/HAL/STM32/fastio.h
+++ b/Marlin/src/HAL/STM32/fastio.h
@@ -63,7 +63,7 @@ void FastIO_init(); // Must be called before using fast io macros
#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(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)
@@ -73,9 +73,9 @@ void FastIO_init(); // Must be called before using fast io macros
#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_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)
diff --git a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h
index 5ff40debea5e..9069d9f7bd8a 100644
--- a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h
+++ b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h
@@ -98,7 +98,7 @@ static inline void pwm_details(const pin_t pin) {
timer_dev * const tdev = PIN_MAP[pin].timer_device;
const uint8_t channel = PIN_MAP[pin].timer_channel;
const char num = (
- #if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+ #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
tdev == &timer8 ? '8' :
tdev == &timer5 ? '5' :
#endif
diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp
index f11fab39dbad..3a080d5e271e 100644
--- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp
+++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp
@@ -87,7 +87,7 @@ void TFT_FSMC::Init() {
__HAL_RCC_FSMC_CLK_ENABLE();
- for(uint16_t i = 0; PinMap_FSMC[i].pin != NC; i++)
+ 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);
diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp
index 49e64da6a113..921e377a9f4e 100644
--- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp
+++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp
@@ -155,9 +155,9 @@ uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) {
uint16_t XPT2046::HardwareIO(uint16_t data) {
__HAL_SPI_ENABLE(&SPIx);
- while((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {}
+ while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {}
SPIx.Instance->DR = data;
- while((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {}
+ while ((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {}
__HAL_SPI_DISABLE(&SPIx);
return SPIx.Instance->DR;
diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp
index d7f9264be6c9..cd1efc16591d 100644
--- a/Marlin/src/HAL/STM32F1/HAL.cpp
+++ b/Marlin/src/HAL/STM32F1/HAL.cpp
@@ -97,6 +97,9 @@ const uint8_t adc_pins[] = {
#if HAS_TEMP_ADC_0
TEMP_0_PIN,
#endif
+ #if HAS_TEMP_ADC_PROBE
+ TEMP_PROBE_PIN,
+ #endif
#if HAS_HEATED_BED
TEMP_BED_PIN,
#endif
@@ -151,6 +154,9 @@ enum TempPinIndex : char {
#if HAS_TEMP_ADC_0
TEMP_0,
#endif
+ #if HAS_TEMP_ADC_PROBE
+ TEMP_PROBE,
+ #endif
#if HAS_HEATED_BED
TEMP_BED,
#endif
@@ -341,6 +347,9 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
#if HAS_TEMP_ADC_0
case TEMP_0_PIN: pin_index = TEMP_0; break;
#endif
+ #if HAS_TEMP_ADC_PROBE
+ case TEMP_PROBE_PIN: pin_index = TEMP_PROBE; break;
+ #endif
#if HAS_HEATED_BED
case TEMP_BED_PIN: pin_index = TEMP_BED; break;
#endif
diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h
index f76d8c54a0e3..c10dea0eafd1 100644
--- a/Marlin/src/HAL/STM32F1/HAL.h
+++ b/Marlin/src/HAL/STM32F1/HAL.h
@@ -53,7 +53,7 @@
// ------------------------
#ifndef STM32_FLASH_SIZE
- #if defined(MCU_STM32F103RE) || defined(MCU_STM32F103VE)
+ #if EITHER(MCU_STM32F103RE, MCU_STM32F103VE)
#define STM32_FLASH_SIZE 512
#else
#define STM32_FLASH_SIZE 256
@@ -68,74 +68,49 @@
#endif
#endif
-#if SERIAL_PORT == 0
- #error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
-#elif SERIAL_PORT == -1
+#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 MYSERIAL0 UsbSerial
-#elif SERIAL_PORT == 1
- #define MYSERIAL0 MSerial1
-#elif SERIAL_PORT == 2
- #define MYSERIAL0 MSerial2
-#elif SERIAL_PORT == 3
- #define MYSERIAL0 MSerial3
-#elif SERIAL_PORT == 4
- #define MYSERIAL0 MSerial4
-#elif SERIAL_PORT == 5
- #define MYSERIAL0 MSerial5
+#elif WITHIN(SERIAL_PORT, 1, NUM_UARTS)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+#elif NUM_UARTS == 5
+ #error "SERIAL_PORT must be -1 or from 1 to 5. Please update your configuration."
#else
- #error "SERIAL_PORT must be from -1 to 5. Please update your configuration."
+ #error "SERIAL_PORT must be -1 or from 1 to 3. Please update your configuration."
#endif
#ifdef SERIAL_PORT_2
- #if SERIAL_PORT_2 == 0
- #error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration."
- #elif SERIAL_PORT_2 == SERIAL_PORT
- #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration."
- #elif SERIAL_PORT_2 == -1
+ #if SERIAL_PORT_2 == -1
#define MYSERIAL1 UsbSerial
- #elif SERIAL_PORT_2 == 1
- #define MYSERIAL1 MSerial1
- #elif SERIAL_PORT_2 == 2
- #define MYSERIAL1 MSerial2
- #elif SERIAL_PORT_2 == 3
- #define MYSERIAL1 MSerial3
- #elif SERIAL_PORT_2 == 4
- #define MYSERIAL1 MSerial4
- #elif SERIAL_PORT_2 == 5
- #define MYSERIAL1 MSerial5
+ #elif WITHIN(SERIAL_PORT_2, 1, NUM_UARTS)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
+ #elif NUM_UARTS == 5
+ #error "SERIAL_PORT_2 must be -1 or from 1 to 5. Please update your configuration."
#else
- #error "SERIAL_PORT_2 must be from -1 to 5. Please update your configuration."
+ #error "SERIAL_PORT_2 must be -1 or from 1 to 3. Please update your configuration."
#endif
- #define NUM_SERIAL 2
-#else
- #define NUM_SERIAL 1
#endif
-#ifdef DGUS_SERIAL
- #if DGUS_SERIAL_PORT == 0
- #error "DGUS_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
- #elif DGUS_SERIAL_PORT == SERIAL_PORT
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
- #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
- #elif DGUS_SERIAL_PORT == -1
- #define DGUS_SERIAL UsbSerial
- #elif DGUS_SERIAL_PORT == 1
- #define DGUS_SERIAL MSerial1
- #elif DGUS_SERIAL_PORT == 2
- #define DGUS_SERIAL MSerial2
- #elif DGUS_SERIAL_PORT == 3
- #define DGUS_SERIAL MSerial3
- #elif DGUS_SERIAL_PORT == 4
- #define DGUS_SERIAL MSerial4
- #elif DGUS_SERIAL_PORT == 5
- #define DGUS_SERIAL MSerial5
+#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)
+ #elif NUM_UARTS == 5
+ #error "LCD_SERIAL_PORT must be -1 or from 1 to 5. Please update your configuration."
#else
- #error "DGUS_SERIAL_PORT must be from -1 to 5. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be -1 or from 1 to 3. Please update your configuration."
#endif
#endif
-
// Set interrupt grouping for this MCU
void HAL_init();
#define HAL_IDLETASK 1
@@ -210,6 +185,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
void _delay_ms(const int delay);
#pragma GCC diagnostic push
diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
index 4d72473e7f8e..76b1c3e2468b 100644
--- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
+++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
@@ -24,9 +24,6 @@
/**
* Software SPI functions originally from Arduino Sd2Card Library
* Copyright (c) 2009 by William Greiman
- */
-
-/**
* Adapted to the STM32F1 HAL
*/
@@ -113,7 +110,7 @@ void spiInit(uint8_t spiRate) {
* @details
*/
uint8_t spiRec() {
- uint8_t returnByte = SPI.transfer(ff);
+ uint8_t returnByte = SPI.transfer(0xFF);
return returnByte;
}
@@ -157,7 +154,7 @@ void spiSendBlock(uint8_t token, const uint8_t* buf) {
#if ENABLED(SPI_EEPROM)
// Read single byte from specified SPI channel
-uint8_t spiRec(uint32_t chan) { return SPI.transfer(ff); }
+uint8_t spiRec(uint32_t chan) { return SPI.transfer(0xFF); }
// Write single byte to specified SPI channel
void spiSend(uint32_t chan, byte b) { SPI.send(b); }
diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp
index 9a48e901f42d..ebf11cb429fa 100644
--- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp
+++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp
@@ -22,7 +22,7 @@
#ifdef __STM32F1__
-#include "../../inc/MarlinConfigPre.h"
+#include "../../inc/MarlinConfig.h"
#include "MarlinSerial.h"
#include
@@ -53,7 +53,8 @@ static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb
rb_push_insert(rb, c);
#endif
#if ENABLED(EMERGENCY_PARSER)
- emergency_parser.update(serial.emergency_state, c);
+ if (serial.emergency_parser_enabled())
+ emergency_parser.update(serial.emergency_state, c);
#endif
}
}
@@ -73,40 +74,120 @@ static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb
}
}
-#define DEFINE_HWSERIAL_MARLIN(name, n) \
- MarlinSerial name(USART##n, \
- BOARD_USART##n##_TX_PIN, \
- BOARD_USART##n##_RX_PIN); \
- extern "C" void __irq_usart##n(void) { \
+// Not every MarlinSerial port should handle emergency parsing.
+// It would not make sense to parse GCode from TMC responses, for example.
+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 DEFINE_HWSERIAL_MARLIN(name, n) \
+ MarlinSerial name(USART##n, \
+ BOARD_USART##n##_TX_PIN, \
+ BOARD_USART##n##_RX_PIN, \
+ serial_handles_emergency(n)); \
+ extern "C" void __irq_usart##n(void) { \
my_usart_irq(USART##n->rb, USART##n->wb, USART##n##_BASE, MSerial##n); \
}
#define DEFINE_HWSERIAL_UART_MARLIN(name, n) \
MarlinSerial name(UART##n, \
- BOARD_USART##n##_TX_PIN, \
- BOARD_USART##n##_RX_PIN); \
+ BOARD_USART##n##_TX_PIN, \
+ BOARD_USART##n##_RX_PIN, \
+ serial_handles_emergency(n)); \
extern "C" void __irq_usart##n(void) { \
- my_usart_irq(USART##n->rb, USART##n->wb, USART##n##_BASE, MSerial##n); \
+ my_usart_irq(UART##n->rb, UART##n->wb, UART##n##_BASE, MSerial##n); \
}
-#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1
- DEFINE_HWSERIAL_MARLIN(MSerial1, 1);
+// Instantiate all UARTs even if they are not needed
+// This avoids a bunch of logic to figure out every serial
+// port which may be in use on the system.
+DEFINE_HWSERIAL_MARLIN(MSerial1, 1);
+DEFINE_HWSERIAL_MARLIN(MSerial2, 2);
+DEFINE_HWSERIAL_MARLIN(MSerial3, 3);
+#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
+ DEFINE_HWSERIAL_UART_MARLIN(MSerial4, 4);
+ DEFINE_HWSERIAL_UART_MARLIN(MSerial5, 5);
#endif
-#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2
- DEFINE_HWSERIAL_MARLIN(MSerial2, 2);
-#endif
+// 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; }
-#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3
- DEFINE_HWSERIAL_MARLIN(MSerial3, 3);
-#endif
+#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");
-#if SERIAL_PORT == 4 || SERIAL_PORT_2 == 4 || DGUS_SERIAL_PORT == 4
- DEFINE_HWSERIAL_UART_MARLIN(MSerial4, 4);
-#endif
+// If you encounter this error, replace SerialX with MSerialX, for example MSerial3.
-#if SERIAL_PORT == 5 || SERIAL_PORT_2 == 5 || DGUS_SERIAL_PORT == 5
- DEFINE_HWSERIAL_UART_MARLIN(MSerial5, 5);
+// Non-TMC ports were already validated in HAL.h, so do not require verbose error messages.
+#ifdef MYSERIAL0
+ CHECK_CFG_SERIAL(MYSERIAL0);
+#endif
+#ifdef MYSERIAL1
+ CHECK_CFG_SERIAL(MYSERIAL1);
+#endif
+#ifdef 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(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 // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.h b/Marlin/src/HAL/STM32F1/MarlinSerial.h
index eb0059bfbcae..6aa94b64fff7 100644
--- a/Marlin/src/HAL/STM32F1/MarlinSerial.h
+++ b/Marlin/src/HAL/STM32F1/MarlinSerial.h
@@ -30,19 +30,27 @@
#include "../../feature/e_parser.h"
#endif
+// Increase priority of serial interrupts, to reduce overflow errors
#define UART_IRQ_PRIO 1
class MarlinSerial : public HardwareSerial {
public:
- MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) :
+ #if ENABLED(EMERGENCY_PARSER)
+ const bool ep_enabled;
+ EmergencyParser::State emergency_state;
+ inline bool emergency_parser_enabled() { return ep_enabled; }
+ #endif
+
+ MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin, bool TERN_(EMERGENCY_PARSER, ep_capable)) :
HardwareSerial(usart_device, tx_pin, rx_pin)
#if ENABLED(EMERGENCY_PARSER)
+ , ep_enabled(ep_capable)
, emergency_state(EmergencyParser::State::EP_RESET)
#endif
{ }
#ifdef UART_IRQ_PRIO
- // shadow the parent methods to set irq priority after the begin
+ // Shadow the parent methods to set IRQ priority after begin()
void begin(uint32 baud) {
MarlinSerial::begin(baud, SERIAL_8N1);
}
@@ -52,14 +60,12 @@ class MarlinSerial : public HardwareSerial {
nvic_irq_set_priority(c_dev()->irq_num, UART_IRQ_PRIO);
}
#endif
-
- #if ENABLED(EMERGENCY_PARSER)
- EmergencyParser::State emergency_state;
- #endif
};
extern MarlinSerial MSerial1;
extern MarlinSerial MSerial2;
extern MarlinSerial MSerial3;
-extern MarlinSerial MSerial4;
-extern MarlinSerial MSerial5;
+#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
+ extern MarlinSerial MSerial4;
+ extern MarlinSerial MSerial5;
+#endif
diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
index 894abb882a64..f88fa8850788 100644
--- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
+++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
@@ -20,7 +20,7 @@
#include "../../../inc/MarlinConfig.h"
-#if BOTH(HAS_GRAPHICAL_LCD, FORCE_SOFT_SPI)
+#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)
#include "../HAL.h"
#include
@@ -161,5 +161,5 @@ uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val,
return 1;
}
-#endif // HAS_GRAPHICAL_LCD
+#endif // HAS_MARLINUI_U8GLIB
#endif // STM32F1
diff --git a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
index f77306a88a17..658b7cd4a654 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
@@ -25,6 +25,8 @@
* with simple implementations supplied by Marlin.
*/
+#ifdef __STM32F1__
+
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
@@ -79,3 +81,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
}
#endif // IIC_BL24CXX_EEPROM
+#endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
index 33dd277addbe..ccc3fc537f1a 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
@@ -25,6 +25,8 @@
* Enable USE_SHARED_EEPROM if not supplied by the framework.
*/
+#ifdef __STM32F1__
+
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
@@ -49,3 +51,4 @@ uint8_t eeprom_read_byte(uint8_t *pos) {
}
#endif // IIC_BL24CXX_EEPROM
+#endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp
index b4699d00dcc0..fffd6ccaf01e 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp
@@ -17,17 +17,17 @@
* along with this program. If not, see .
*
*/
+
+/**
+ * HAL PersistentStore for STM32F1
+ */
+
#ifdef __STM32F1__
#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"
diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp
index 6a4652e467fb..4f44f2ee905f 100644
--- a/Marlin/src/HAL/STM32F1/msc_sd.cpp
+++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp
@@ -13,7 +13,7 @@
* along with this program. If not, see .
*
*/
-#ifdef USE_USB_COMPOSITE
+#if defined(__STM32F1__) && defined(USE_USB_COMPOSITE)
#include "msc_sd.h"
#include "SPI.h"
@@ -77,4 +77,4 @@ void MSC_SD_init() {
#endif
}
-#endif // USE_USB_COMPOSITE
+#endif // __STM32F1__ && USE_USB_COMPOSITE
diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h
index d9cdbe6bb3d1..1e4e4c44b1b5 100644
--- a/Marlin/src/HAL/STM32F1/msc_sd.h
+++ b/Marlin/src/HAL/STM32F1/msc_sd.h
@@ -32,6 +32,7 @@ class MarlinUSBCompositeSerial : public USBCompositeSerial {
#if ENABLED(EMERGENCY_PARSER)
EmergencyParser::State emergency_state;
+ inline bool emergency_parser_enabled() { return true; }
#endif
};
diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp
index 099e2a06869f..9c2b128ddc9a 100644
--- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp
+++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp
@@ -9,9 +9,10 @@
* No restriction on use. You can use, modify and redistribute it for
* personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY.
* Redistributions of source code must retain the above copyright notice.
- *
*/
+#ifdef __STM32F1__
+
#include "../../inc/MarlinConfig.h"
#if SD_CONNECTION_IS(ONBOARD)
@@ -21,23 +22,23 @@
#include "fastio.h"
#if HAS_SHARED_MEDIA
- #ifndef ON_BOARD_SPI_DEVICE
- #define ON_BOARD_SPI_DEVICE SPI_DEVICE
+ #ifndef ONBOARD_SPI_DEVICE
+ #define ONBOARD_SPI_DEVICE SPI_DEVICE
#endif
#define ONBOARD_SD_SPI SPI
#else
- SPIClass OnBoardSPI(ON_BOARD_SPI_DEVICE);
- #define ONBOARD_SD_SPI OnBoardSPI
+ SPIClass OnboardSPI(ONBOARD_SPI_DEVICE);
+ #define ONBOARD_SD_SPI OnboardSPI
#endif
-#if ON_BOARD_SPI_DEVICE == 1
+#if ONBOARD_SPI_DEVICE == 1
#define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_4
#else
#define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_2
#endif
-#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) /* Set OnBoardSPI cs low */
-#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) /* Set OnBoardSPI cs high */
+#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) /* Set OnboardSPI cs low */
+#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) /* Set OnboardSPI cs high */
#define FCLK_FAST() ONBOARD_SD_SPI.setClockDivider(SPI_CLOCK_MAX)
#define FCLK_SLOW() ONBOARD_SD_SPI.setClockDivider(SPI_BAUD_PCLK_DIV_256)
@@ -152,7 +153,7 @@ static int select() { /* 1:OK, 0:Timeout */
/*-----------------------------------------------------------------------*/
static void power_on() { /* Enable SSP module and attach it to I/O pads */
- ONBOARD_SD_SPI.setModule(ON_BOARD_SPI_DEVICE);
+ ONBOARD_SD_SPI.setModule(ONBOARD_SPI_DEVICE);
ONBOARD_SD_SPI.begin();
ONBOARD_SD_SPI.setBitOrder(MSBFIRST);
ONBOARD_SD_SPI.setDataMode(SPI_MODE0);
@@ -554,3 +555,4 @@ DRESULT disk_read (
#endif // _DISKIO_IOCTL
#endif // SD_CONNECTION_IS(ONBOARD)
+#endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp
index 0e9a3b2d0450..ffa6db1206ae 100644
--- a/Marlin/src/HAL/STM32F1/sdio.cpp
+++ b/Marlin/src/HAL/STM32F1/sdio.cpp
@@ -26,7 +26,7 @@
#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
-#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
#include "sdio.h"
diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp
index bc1b012dc788..008301d9bc0c 100644
--- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp
+++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp
@@ -89,6 +89,16 @@ void TFT_FSMC::Init() {
uint8_t cs = FSMC_CS_PIN, rs = FSMC_RS_PIN;
uint32_t controllerAddress;
+ #if PIN_EXISTS(TFT_BACKLIGHT)
+ OUT_WRITE(TFT_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT));
+ #endif
+
+ #if ENABLED(LCD_USE_DMA_FSMC)
+ dma_init(FSMC_DMA_DEV);
+ dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
+ dma_set_priority(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, DMA_PRIORITY_MEDIUM);
+ #endif
+
#if PIN_EXISTS(TFT_RESET)
OUT_WRITE(TFT_RESET_PIN, HIGH);
delay(100);
@@ -201,6 +211,8 @@ uint32_t TFT_FSMC::GetID() {
id = ReadID(LCD_READ_ID);
if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
id = ReadID(LCD_READ_ID4);
+ if ((id & 0xFF00) == 0 && (id & 0xFF) != 0)
+ id = ReadID(LCD_READ_ID4);
return id;
}
diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h
index 5601400c5ac9..00a65de7926f 100644
--- a/Marlin/src/HAL/STM32_F4_F7/HAL.h
+++ b/Marlin/src/HAL/STM32_F4_F7/HAL.h
@@ -46,24 +46,16 @@
// Serial override
//extern HalSerial usb_serial;
+#define _MSERIAL(X) SerialUART##X
+#define MSERIAL(X) _MSERIAL(X)
+#define SerialUART0 Serial1
+
#if defined(STM32F4) && SERIAL_PORT == 0
#error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
#elif SERIAL_PORT == -1
#define MYSERIAL0 SerialUSB
-#elif SERIAL_PORT == 0
- #define MYSERIAL0 Serial1
-#elif SERIAL_PORT == 1
- #define MYSERIAL0 SerialUART1
-#elif SERIAL_PORT == 2
- #define MYSERIAL0 SerialUART2
-#elif SERIAL_PORT == 3
- #define MYSERIAL0 SerialUART3
-#elif SERIAL_PORT == 4
- #define MYSERIAL0 SerialUART4
-#elif SERIAL_PORT == 5
- #define MYSERIAL0 SerialUART5
-#elif SERIAL_PORT == 6
- #define MYSERIAL0 SerialUART6
+#elif WITHIN(SERIAL_PORT, 0, 6)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
#else
#error "SERIAL_PORT must be from -1 to 6. Please update your configuration."
#endif
@@ -71,57 +63,24 @@
#ifdef SERIAL_PORT_2
#if defined(STM32F4) && SERIAL_PORT_2 == 0
#error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration."
- #elif SERIAL_PORT_2 == SERIAL_PORT
- #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration."
#elif SERIAL_PORT_2 == -1
#define MYSERIAL1 SerialUSB
- #elif SERIAL_PORT_2 == 0
- #define MYSERIAL1 Serial1
- #elif SERIAL_PORT_2 == 1
- #define MYSERIAL1 SerialUART1
- #elif SERIAL_PORT_2 == 2
- #define MYSERIAL1 SerialUART2
- #elif SERIAL_PORT_2 == 3
- #define MYSERIAL1 SerialUART3
- #elif SERIAL_PORT_2 == 4
- #define MYSERIAL1 SerialUART4
- #elif SERIAL_PORT_2 == 5
- #define MYSERIAL1 SerialUART5
- #elif SERIAL_PORT_2 == 6
- #define MYSERIAL1 SerialUART6
+ #elif WITHIN(SERIAL_PORT_2, 0, 6)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
#else
#error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration."
#endif
- #define NUM_SERIAL 2
-#else
- #define NUM_SERIAL 1
#endif
-#ifdef DGUS_SERIAL_PORT
- #if defined(STM32F4) && DGUS_SERIAL_PORT == 0
- #error "DGUS_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
- #elif DGUS_SERIAL_PORT == SERIAL_PORT
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
- #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
- #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
- #elif DGUS_SERIAL_PORT == -1
- #define DGUS_SERIAL SerialUSB
- #elif DGUS_SERIAL_PORT == 0
- #define DGUS_SERIAL Serial1
- #elif DGUS_SERIAL_PORT == 1
- #define DGUS_SERIAL SerialUART1
- #elif DGUS_SERIAL_PORT == 2
- #define DGUS_SERIAL SerialUART2
- #elif DGUS_SERIAL_PORT == 3
- #define DGUS_SERIAL SerialUART3
- #elif DGUS_SERIAL_PORT == 4
- #define DGUS_SERIAL SerialUART4
- #elif DGUS_SERIAL_PORT == 5
- #define DGUS_SERIAL SerialUART5
- #elif DGUS_SERIAL_PORT == 6
- #define DGUS_SERIAL SerialUART6
+#ifdef LCD_SERIAL_PORT
+ #if defined(STM32F4) && LCD_SERIAL_PORT == 0
+ #error "LCD_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
+ #elif LCD_SERIAL_PORT == -1
+ #define LCD_SERIAL SerialUSB
+ #elif WITHIN(LCD_SERIAL_PORT, 0, 6)
+ #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
- #error "DGUS_SERIAL_PORT must be from -1 to 6. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from -1 to 6. Please update your configuration."
#endif
#endif
@@ -183,6 +142,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
void _delay_ms(const int delay);
/*
diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp
index 4d116f440b8e..e67808c3c458 100644
--- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp
@@ -22,7 +22,6 @@
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
- *
*/
#if defined(STM32GENERIC) && defined(STM32F7)
@@ -46,8 +45,8 @@
#define DEFAULT_MICROSTEPPING_VALUE 32
//TMC26X register definitions
-#define DRIVER_CONTROL_REGISTER 0x0ul
-#define CHOPPER_CONFIG_REGISTER 0x80000ul
+#define DRIVER_CONTROL_REGISTER 0x0UL
+#define CHOPPER_CONFIG_REGISTER 0x80000UL
#define COOL_STEP_REGISTER 0xA0000ul
#define STALL_GUARD2_LOAD_MEASURE_REGISTER 0xC0000ul
#define DRIVER_CONFIG_REGISTER 0xE0000ul
@@ -56,58 +55,58 @@
//definitions for the driver control register
#define MICROSTEPPING_PATTERN 0xFul
-#define STEP_INTERPOLATION 0x200ul
-#define DOUBLE_EDGE_STEP 0x100ul
-#define VSENSE 0x40ul
-#define READ_MICROSTEP_POSTION 0x0ul
-#define READ_STALL_GUARD_READING 0x10ul
-#define READ_STALL_GUARD_AND_COOL_STEP 0x20ul
-#define READ_SELECTION_PATTERN 0x30ul
+#define STEP_INTERPOLATION 0x200UL
+#define DOUBLE_EDGE_STEP 0x100UL
+#define VSENSE 0x40UL
+#define READ_MICROSTEP_POSTION 0x0UL
+#define READ_STALL_GUARD_READING 0x10UL
+#define READ_STALL_GUARD_AND_COOL_STEP 0x20UL
+#define READ_SELECTION_PATTERN 0x30UL
//definitions for the chopper config register
-#define CHOPPER_MODE_STANDARD 0x0ul
-#define CHOPPER_MODE_T_OFF_FAST_DECAY 0x4000ul
+#define CHOPPER_MODE_STANDARD 0x0UL
+#define CHOPPER_MODE_T_OFF_FAST_DECAY 0x4000UL
#define T_OFF_PATTERN 0xFul
-#define RANDOM_TOFF_TIME 0x2000ul
-#define BLANK_TIMING_PATTERN 0x18000ul
+#define RANDOM_TOFF_TIME 0x2000UL
+#define BLANK_TIMING_PATTERN 0x18000UL
#define BLANK_TIMING_SHIFT 15
-#define HYSTERESIS_DECREMENT_PATTERN 0x1800ul
+#define HYSTERESIS_DECREMENT_PATTERN 0x1800UL
#define HYSTERESIS_DECREMENT_SHIFT 11
-#define HYSTERESIS_LOW_VALUE_PATTERN 0x780ul
+#define HYSTERESIS_LOW_VALUE_PATTERN 0x780UL
#define HYSTERESIS_LOW_SHIFT 7
-#define HYSTERESIS_START_VALUE_PATTERN 0x78ul
+#define HYSTERESIS_START_VALUE_PATTERN 0x78UL
#define HYSTERESIS_START_VALUE_SHIFT 4
#define T_OFF_TIMING_PATERN 0xFul
//definitions for cool step register
-#define MINIMUM_CURRENT_FOURTH 0x8000ul
-#define CURRENT_DOWN_STEP_SPEED_PATTERN 0x6000ul
+#define MINIMUM_CURRENT_FOURTH 0x8000UL
+#define CURRENT_DOWN_STEP_SPEED_PATTERN 0x6000UL
#define SE_MAX_PATTERN 0xF00ul
-#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60ul
+#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60UL
#define SE_MIN_PATTERN 0xFul
//definitions for StallGuard2 current register
-#define STALL_GUARD_FILTER_ENABLED 0x10000ul
+#define STALL_GUARD_FILTER_ENABLED 0x10000UL
#define STALL_GUARD_TRESHHOLD_VALUE_PATTERN 0x17F00ul
#define CURRENT_SCALING_PATTERN 0x1Ful
#define STALL_GUARD_CONFIG_PATTERN 0x17F00ul
#define STALL_GUARD_VALUE_PATTERN 0x7F00ul
//definitions for the input from the TMC2660
-#define STATUS_STALL_GUARD_STATUS 0x1ul
-#define STATUS_OVER_TEMPERATURE_SHUTDOWN 0x2ul
-#define STATUS_OVER_TEMPERATURE_WARNING 0x4ul
-#define STATUS_SHORT_TO_GROUND_A 0x8ul
-#define STATUS_SHORT_TO_GROUND_B 0x10ul
-#define STATUS_OPEN_LOAD_A 0x20ul
-#define STATUS_OPEN_LOAD_B 0x40ul
-#define STATUS_STAND_STILL 0x80ul
+#define STATUS_STALL_GUARD_STATUS 0x1UL
+#define STATUS_OVER_TEMPERATURE_SHUTDOWN 0x2UL
+#define STATUS_OVER_TEMPERATURE_WARNING 0x4UL
+#define STATUS_SHORT_TO_GROUND_A 0x8UL
+#define STATUS_SHORT_TO_GROUND_B 0x10UL
+#define STATUS_OPEN_LOAD_A 0x20UL
+#define STATUS_OPEN_LOAD_B 0x40UL
+#define STATUS_STAND_STILL 0x80UL
#define READOUT_VALUE_PATTERN 0xFFC00ul
#define CPU_32_BIT
//default values
-#define INITIAL_MICROSTEPPING 0x3ul //32th microstepping
+#define INITIAL_MICROSTEPPING 0x3UL //32th microstepping
SPIClass SPI_6(SPI6, SPI6_MOSI_PIN, SPI6_MISO_PIN, SPI6_SCK_PIN);
@@ -662,7 +661,6 @@ boolean TMC26XStepper::isEnabled() { return !!(chopper_config_register & T_OFF_P
/**
* reads a value from the TMC26X status register. The value is not obtained directly but can then
* be read by the various status routines.
- *
*/
void TMC26XStepper::readStatus(char read_value) {
uint32_t old_driver_configuration_register_value = driver_configuration_register_value;
diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h
index f1d0133a3b14..208c3bc7e062 100644
--- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h
+++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h
@@ -22,7 +22,6 @@
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
- *
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp
index d276a4c88084..8c3dd8337740 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp
@@ -20,9 +20,8 @@
*
*/
-
/**
- * Description: HAL for Teensy32 (MK20DX256)
+ * HAL for Teensy 3.2 (MK20DX256)
*/
#ifdef __MK20DX256__
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h
index ad095cba83cc..8ab358e9e1e5 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL.h
+++ b/Marlin/src/HAL/TEENSY31_32/HAL.h
@@ -22,7 +22,7 @@
#pragma once
/**
- * Description: HAL for Teensy 3.5 and Teensy 3.6
+ * HAL for Teensy 3.2 (MK20DX256)
*/
#define CPU_32_BIT
@@ -44,23 +44,20 @@
//#undef MOTHERBOARD
//#define MOTHERBOARD BOARD_TEENSY31_32
-#ifdef __MK20DX256__
- #define IS_32BIT_TEENSY 1
+#define IS_32BIT_TEENSY 1
+#define IS_TEENSY_31_32 1
+#ifndef IS_TEENSY31
#define IS_TEENSY32 1
#endif
-#define NUM_SERIAL 1
+#define _MSERIAL(X) Serial##X
+#define MSERIAL(X) _MSERIAL(X)
+#define Serial0 Serial
#if SERIAL_PORT == -1
#define MYSERIAL0 SerialUSB
-#elif SERIAL_PORT == 0
- #define MYSERIAL0 Serial
-#elif SERIAL_PORT == 1
- #define MYSERIAL0 Serial1
-#elif SERIAL_PORT == 2
- #define MYSERIAL0 Serial2
-#elif SERIAL_PORT == 3
- #define MYSERIAL0 Serial3
+#elif WITHIN(SERIAL_PORT, 0, 3)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
#endif
#define HAL_SERVO_LIB libServo
@@ -68,7 +65,7 @@
typedef int8_t pin_t;
#ifndef analogInputToDigitalPin
- #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
+ #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq()
@@ -96,6 +93,8 @@ void HAL_clear_reset_source();
// Get the reason for the reset
uint8_t HAL_get_reset_source();
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push
diff --git a/Marlin/src/HAL/TEENSY31_32/Servo.cpp b/Marlin/src/HAL/TEENSY31_32/Servo.cpp
index 544892cb7de4..19d57cf1b375 100644
--- a/Marlin/src/HAL/TEENSY31_32/Servo.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/Servo.cpp
@@ -51,5 +51,4 @@ void libServo::move(const int value) {
}
#endif // HAS_SERVOS
-
#endif // __MK20DX256__
diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp
index f66313225562..cc5c56f7d550 100644
--- a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp
@@ -23,8 +23,7 @@
#if USE_WIRED_EEPROM
/**
- * PersistentStore for Arduino-style EEPROM interface
- * with implementations supplied by the framework.
+ * HAL PersistentStore for Teensy 3.2 (MK20DX256)
*/
#include "../shared/eeprom_api.h"
diff --git a/Marlin/src/HAL/TEENSY31_32/timers.cpp b/Marlin/src/HAL/TEENSY31_32/timers.cpp
index bf756af8a128..7e01a38f8946 100644
--- a/Marlin/src/HAL/TEENSY31_32/timers.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/timers.cpp
@@ -21,7 +21,7 @@
*/
/**
- * Teensy3.2 __MK20DX256__
+ * HAL Timers for Teensy 3.2 (MK20DX256)
*/
#ifdef __MK20DX256__
diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h
index 4f004ef75191..135b32883084 100644
--- a/Marlin/src/HAL/TEENSY31_32/timers.h
+++ b/Marlin/src/HAL/TEENSY31_32/timers.h
@@ -22,8 +22,7 @@
#pragma once
/**
- * Description: HAL for
- * Teensy3.2 (__MK20DX256__)
+ * HAL Timers for Teensy 3.2 (MK20DX256)
*/
#include
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp
index bcbee1d4c5ff..92907353b833 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp
@@ -21,7 +21,7 @@
*/
/**
- * Description: HAL for Teensy35 (MK64FX512)
+ * HAL for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h
index 96be08d7b7ca..2b735d6224f4 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL.h
+++ b/Marlin/src/HAL/TEENSY35_36/HAL.h
@@ -22,7 +22,7 @@
#pragma once
/**
- * Description: HAL for Teensy 3.5 and Teensy 3.6
+ * HAL for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#define CPU_32_BIT
@@ -45,27 +45,22 @@
// Defines
// ------------------------
-#ifdef __MK64FX512__
- #define IS_32BIT_TEENSY 1
- #define IS_TEENSY35 1
-#endif
+#define IS_32BIT_TEENSY 1
+#define IS_TEENSY_35_36 1
#ifdef __MK66FX1M0__
- #define IS_32BIT_TEENSY 1
#define IS_TEENSY36 1
+#else // __MK64FX512__
+ #define IS_TEENSY35 1
#endif
-#define NUM_SERIAL 1
+#define _MSERIAL(X) Serial##X
+#define MSERIAL(X) _MSERIAL(X)
+#define Serial0 Serial
#if SERIAL_PORT == -1
#define MYSERIAL0 SerialUSB
-#elif SERIAL_PORT == 0
- #define MYSERIAL0 Serial
-#elif SERIAL_PORT == 1
- #define MYSERIAL0 Serial1
-#elif SERIAL_PORT == 2
- #define MYSERIAL0 Serial2
-#elif SERIAL_PORT == 3
- #define MYSERIAL0 Serial3
+#elif WITHIN(SERIAL_PORT, 0, 3)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
#endif
#define HAL_SERVO_LIB libServo
@@ -73,7 +68,7 @@
typedef int8_t pin_t;
#ifndef analogInputToDigitalPin
- #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
+ #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq()
@@ -104,6 +99,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
index 812aa90c83b3..b36900a32195 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
@@ -19,6 +19,11 @@
* along with this program. If not, see .
*
*/
+
+/**
+ * HAL SPI for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
+ */
+
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "HAL.h"
diff --git a/Marlin/src/HAL/TEENSY35_36/Servo.cpp b/Marlin/src/HAL/TEENSY35_36/Servo.cpp
index d1390187a71e..033858594f6c 100644
--- a/Marlin/src/HAL/TEENSY35_36/Servo.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/Servo.cpp
@@ -19,6 +19,11 @@
* along with this program. If not, see .
*
*/
+
+/**
+ * HAL Servo for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
+ */
+
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "../../inc/MarlinConfig.h"
@@ -51,5 +56,4 @@ void libServo::move(const int value) {
}
#endif // HAS_SERVOS
-
#endif // __MK64FX512__ || __MK66FX1M0__
diff --git a/Marlin/src/HAL/TEENSY35_36/Servo.h b/Marlin/src/HAL/TEENSY35_36/Servo.h
index ae904f0e2e62..719011f102a0 100644
--- a/Marlin/src/HAL/TEENSY35_36/Servo.h
+++ b/Marlin/src/HAL/TEENSY35_36/Servo.h
@@ -21,6 +21,10 @@
*/
#pragma once
+/**
+ * HAL Servo for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
+ */
+
#include
// Inherit and expand on core Servo library
diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
index d2d7324cdd97..ccbdc6b11600 100644
--- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
@@ -22,15 +22,14 @@
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
+/**
+ * HAL PersistentStore for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
+ */
+
#include "../../inc/MarlinConfig.h"
#if USE_WIRED_EEPROM
-/**
- * PersistentStore for Arduino-style EEPROM interface
- * with implementations supplied by the framework.
- */
-
#include "../shared/eeprom_api.h"
#include
diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
index 92e22efc0fe6..87e6a7507abc 100644
--- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
+++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
@@ -22,7 +22,7 @@
#pragma once
/**
- * Endstop Interrupts
+ * HAL Endstop Interrupts for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*
* Without endstop interrupts the endstop pins must be polled continually in
* the temperature-ISR via endstops.update(), most of the time finding no change.
diff --git a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
index e57c73c59558..e529fa93be16 100644
--- a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
+++ b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
@@ -18,6 +18,10 @@
*/
#pragma once
+/**
+ * HAL Pins Debugging for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
+ */
+
#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
diff --git a/Marlin/src/HAL/TEENSY35_36/spi_pins.h b/Marlin/src/HAL/TEENSY35_36/spi_pins.h
index 276d4f456a7f..c76344d07546 100644
--- a/Marlin/src/HAL/TEENSY35_36/spi_pins.h
+++ b/Marlin/src/HAL/TEENSY35_36/spi_pins.h
@@ -21,6 +21,10 @@
*/
#pragma once
+/**
+ * HAL SPI Pins for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
+ */
+
#define SCK_PIN 13
#define MISO_PIN 12
#define MOSI_PIN 11
diff --git a/Marlin/src/HAL/TEENSY35_36/timers.cpp b/Marlin/src/HAL/TEENSY35_36/timers.cpp
index 5725e83a85da..8067d091dd01 100644
--- a/Marlin/src/HAL/TEENSY35_36/timers.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/timers.cpp
@@ -21,8 +21,7 @@
*/
/**
- * Teensy3.5 __MK64FX512__
- * Teensy3.6 __MK66FX1M0__
+ * HAL Timers for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h
index 68060d0e1c06..5c623cd80192 100644
--- a/Marlin/src/HAL/TEENSY35_36/timers.h
+++ b/Marlin/src/HAL/TEENSY35_36/timers.h
@@ -16,13 +16,12 @@
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see